diff --git a/GSMP/motion_automata/automata/HelperFunctions.py b/GSMP/motion_automata/automata/HelperFunctions.py new file mode 100644 index 0000000000000000000000000000000000000000..41c43f3293ad94da71fbd910a374719dfc7b4157 --- /dev/null +++ b/GSMP/motion_automata/automata/HelperFunctions.py @@ -0,0 +1,258 @@ +import sys +sys.path.append("../../GSMP/tools/") +sys.path.append("../../GSMP/tools/commonroad-collision-checker") +sys.path.append("../../GSMP/tools/commonroad-road-boundary") +sys.path.append("../../GSMP/motion_automata/vehicle_model") + +import os +import time +from multiprocessing import Manager, Process + +import numpy as np +from math import atan2 + +import matplotlib.pyplot as plt +from IPython import display +from ipywidgets import widgets + +# import CommonRoad-io modules +from commonroad.visualization.draw_dispatch_cr import draw_object +from commonroad.common.file_reader import CommonRoadFileReader +from commonroad.scenario.trajectory import Trajectory, State +from commonroad.geometry.shape import Rectangle +from commonroad.prediction.prediction import TrajectoryPrediction +from commonroad_cc.collision_detection.pycrcc_collision_dispatch import create_collision_object +from commonroad_cc.visualization.draw_dispatch import draw_object as draw_it +from commonroad.common.solution_writer import CommonRoadSolutionWriter, VehicleType, CostFunction + +# import Motion Automata modules +from automata.MotionAutomata import MotionAutomata +from automata.MotionPrimitive import MotionPrimitive +from automata.States import FinalState + +# ================================== scenario ================================== # +def load_scenario(scenario_path): + # open and read in scenario and planning problem set + scenario, planning_problem_set = CommonRoadFileReader(scenario_path).open() + + return scenario, planning_problem_set + + +# ================================== automata ================================== # +def generate_automata(veh_type_id: int): + """ + 1. We first create a Motion Automata object, then load pre-computed motion primitives into it. + Note that every motion primitive is a short trajectory with varied initial states that lead to different final states. + + 2. We create a connectivity list for every pritimive in the Motion Automata, + which contains all connectable primitives from the focused primitive. + If the velocity and steering angel of the start state of primitive B match + those of the final state of primitive A, we say B is connectable from A. + """ + + # the primitives vary for different vehicle models 1, 2 and 3. + assert veh_type_id in (1,2,3), "Input vehicle type id is not valid! Must be either 1, 2 or 3." + + # step 1 + automata = MotionAutomata(veh_type_id) + + prefix = '../../GSMP/motion_automata/motion_primitives/' + print("Reading motion primitives...") + + if veh_type_id == 1: + automata.readFromXML(prefix + 'V_0.0_20.0_Vstep_1.0_SA_-0.91_0.91_SAstep_0.23_T_0.5_Model_FORD_ESCORT.xml') + elif veh_type_id == 2: + automata.readFromXML(prefix + 'V_0.0_20.0_Vstep_1.0_SA_-1.066_1.066_SAstep_0.27_T_0.5_Model_BMW320i.xml') + elif veh_type_id == 3: + automata.readFromXML(prefix + 'V_0.0_20.0_Vstep_1.0_SA_-1.023_1.023_SAstep_0.26_T_0.5_Model_VW_VANAGON.xml') + + # step 2 + automata.createConnectivityLists() + + # assign vehicle type id to all primitives + automata.setVehicleTypeIdPrimitives() + + print("Automata created.") + print('Number of loaded primitives: ' + str(len(automata.Primitives))) + + return automata + +def add_initial_state_to_automata(automata, planning_problem, flag_print_states = True): + # set initial steering angle to zero + planning_problem.initial_state.steering_angle = 0.0 + + # the initial velocity of the planning problem may be any value, we need to obtain the closest velocity to it + # from StartStates of the primitives in order to get the feasible successors of the planning problem + velocity_closest = automata.getClosestStartVelocity(planning_problem.initial_state.velocity) + planning_problem.initial_state.velocity = velocity_closest + + initial_state = planning_problem.initial_state + goal_region = planning_problem.goal.state_list[0] + + # if flag_print_states: + # print("Initial State:", initial_state) + # print("Goal Region:", goal_region) + + # turn intial state into a motion primitive to check for connectivity to subsequent motion primitives + final_state_primitive = FinalState(x=initial_state.position[0], + y=initial_state.position[1], + steering_angle=initial_state.steering_angle, + velocity=initial_state.velocity, + orientation=initial_state.orientation, + time_step=initial_state.time_step) + + initial_motion_primitive = MotionPrimitive(startState=None, finalState=final_state_primitive, timeStepSize=0, trajectory=None) + + # create connectivity list for this imaginary motion primitive + automata.createConnectivityListPrimitive(initial_motion_primitive) + + return automata, initial_motion_primitive + +# ================================== search for solution ================================== # +""" +1. Searching for a possible solution could be time consuming, and also we would like to visualize the intermediate states during the search. +Thus, we create a separate Process to handle the search, and visualize the intermediate states via Main Process. +More information on python Prcess could be found at [1](https://docs.python.org/3/library/multiprocessing.html) and +[2](http://www.blog.pythonlibrary.org/2016/08/02/python-201-a-multiprocessing-tutorial/). + +2. We need multiprocessing.Manager.Value() to help us share variables between different Processes. + +3. To execute the search, we need to define an individual wrapper function and set it as the target of the new Process. +""" + +def execute_search(motion_planner, initial_motion_primitive, path_shared, dict_status_shared, max_tree_depth): + """ + definition of the wrapper function for search + calls search algorithm and update the status dictionary for visualization in search algorithm + note that dict_status_shared is being shared between difference Processes + """ + result = motion_planner.search_alg(initial_motion_primitive.Successors, max_tree_depth, dict_status_shared) + + # result is in form of (final path, used_primitives) + if result is None: + # no path found + return + else: + display.clear_output(wait=True) + path_shared.value = result[0] + + if len(result[1]) > 0: + print("Found primitives") + + # for primitive in result[1]: + # print('\t', primitive) + +def start_search(scenario, planning_problem, automata, motion_planner, initial_motion_primitive, flag_plot_intermediate_results=True, flag_plot_planning_problem=True): + # create Manager object to manage shared variables between different Processes + process_manager = Manager() + + # create shared variables between Processes + path_shared = process_manager.Value('path_shared', None) + dict_status_shared = process_manager.Value('dict_status_shared', None) + + # initialize status with a dictionary. + # IMPORTANT NOTE: if the shared variable contains complex object types (list, dict, ...), to change its value, + # we need to do it via another object (here dict_status) and pass it to the shared variable at the end + dict_status = {'cost_current': 0, 'path_current':[]} + dict_status_shared.value = dict_status + + # maximum number of concatenated primitives + max_tree_depth = 100 + + # create and start the Process for search + process_search = Process(target=execute_search, + args=(motion_planner, + initial_motion_primitive, + path_shared, + dict_status_shared, + max_tree_depth)) + process_search.start() + + if flag_plot_intermediate_results: + # create a figure, plot the scenario and planning problem + fig = plt.figure(figsize=(9, 9)) + plt.clf() + draw_object(scenario) + if flag_plot_planning_problem: + draw_object(planning_problem) + plt.gca().set_aspect('equal') + plt.gca().set_axis_off() + plt.margins(0,0) + plt.show() + + refresh_rate_plot = 5.0 + + while True: + time.sleep(1 / refresh_rate_plot) + # break the loop if process_search is not alive anymore + if not process_search.is_alive(): + break + + # print current status + string_status = "Cost so far:", round(dict_status_shared.value['cost_current'], 2) + string_status += "Time step:", round(dict_status_shared.value['path_current'][-1].time_step, 2) + string_status += "Orientation:",round(dict_status_shared.value['path_current'][-1].orientation, 2) + string_status += "Velocity:", round(dict_status_shared.value['path_current'][-1].velocity, 2) + print (string_status, end='\r') + + # if there is a path to be visualized + if len(dict_status_shared.value['path_current']) > 0: + if flag_plot_intermediate_results: + plt.clf() + draw_object(scenario) + if flag_plot_planning_problem: + draw_object(planning_problem) + plt.gca().set_aspect('equal') + plt.gca().set_axis_off() + plt.margins(0,0) + plt.show() + + # create a Trajectory from the current states of the path + # Trajectory is essentially a list of states + trajectory = Trajectory(initial_time_step=0, state_list=dict_status_shared.value['path_current']) + + # create an occupancy Prediction via the generated trajectory and shape of ego vehicle + # the Prediction includes a Trajectory and Shape of the object + prediction = TrajectoryPrediction(trajectory=trajectory, shape=automata.egoShape) + + # create a colission object from prediction + # here it is used for visualization purpose + collision_object = create_collision_object(prediction) + + # draw this collision object + draw_it(collision_object, draw_params={'collision': {'facecolor': 'magenta'}}) + + # visualize current trajectory + fig.canvas.draw() + + # wait till process_search terminates + process_search.join() + time.sleep(0.5) + print("Search finished.") + + if path_shared.value is not None and len(path_shared.value) > 1: + print("Solution successfully found :)") + else: + print("Finding solution failed :(") + + return path_shared.value, dict_status_shared.value + +# ================================== visualization ================================== # +def get_state_at_time(t): + for state in path_shared.value: + # return the first state that has time_step >= given t + if state.time_step >= t: + return state + # else return last state + return path[-1] + +def draw_state(t): + print("current time step: ", t) + draw_figure() + + if path_shared is not None: + state = get_state_at_time(t) + trajectory = Trajectory(initial_time_step=int(state.time_step),state_list=[state]) + prediction = TrajectoryPrediction(trajectory=trajectory, shape=automata.egoShape) + collision_object = create_collision_object(prediction) + draw_it(collision_object) \ No newline at end of file diff --git a/GSMP/motion_automata/automata/MotionAutomata.py b/GSMP/motion_automata/automata/MotionAutomata.py new file mode 100644 index 0000000000000000000000000000000000000000..77fb6c11343eaa2f090b5c5de7445901bf72afa6 --- /dev/null +++ b/GSMP/motion_automata/automata/MotionAutomata.py @@ -0,0 +1,100 @@ +import copy +import numpy as np +import xml.etree.ElementTree as et +from automata.MotionPrimitiveParser import MotionPrimitiveParser +from automata.MotionPrimitive import MotionPrimitive +from commonroad.geometry.shape import Rectangle + +class MotionAutomata: + """ + Class to handle motion primitives for motion planning + """ + def __init__(self, veh_type_id): + self.numPrimitives = 0 + self.Primitives = [] + self.veh_type_id = veh_type_id + + self.egoShape = None + if veh_type_id == 1: + self.egoShape = Rectangle(length=4.298, width=1.674) + elif veh_type_id == 2: + self.egoShape = Rectangle(length=4.508, width=1.610) + elif veh_type_id == 3: + self.egoShape = Rectangle(length=4.569, width=1.844) + + def readFromXML(self, filename: str) -> None: + """ + Reads all MotionPrimitives from the given file and stores them in the primitives array. + + :param filename: the name of the file to be read from + """ + # parse XML file + xmlTree = et.parse(filename).getroot() + + # add trajectories + self.numPrimitives = self.numPrimitives + len(xmlTree.findall('Trajectory')) + for t in xmlTree.findall('Trajectory'): + self.Primitives.append(MotionPrimitiveParser.createFromNode(t)) + + self.setVehicleTypeIdPrimitives() + return + + def createConnectivityListPrimitive(self, primitive: MotionPrimitive) -> None: + """ + Creates the successor list for a single primitive and stores them in a successor list of the given primitive. + + :param primitive: the primitive to be connected + """ + for self_primitive in self.Primitives: + if primitive.checkConnectivityToNext(self_primitive): + primitive.Successors.append(self_primitive) + + def createConnectivityLists(self) -> None: + """ + Creates a connectivity list for every primitive (let every primitive has its corresponding successor list). + """ + for self_primitive in self.Primitives: + self.createConnectivityListPrimitive(self_primitive) + return + + def createMirroredPrimitives(self) -> None: + """ + Creates the mirrored motion primitives since the file to load primitives by default only contains left curves. This function computes the right curves. + """ + oldPrimitives = self.Primitives + self.numPrimitives = 2 * self.numPrimitives + self.Primitives = np.empty(self.numPrimitives, dtype=MotionPrimitive) + + for i in range(len(oldPrimitives)): + self.Primitives[i] = oldPrimitives[i] + # create mirrored primitives for the old primitives + newPrimitive = copy.deepcopy(self.Primitives[i]) + newPrimitive.mirror() + # add the new mirrored primitive to self primitive list + self.Primitives[i + len(oldPrimitives)] = newPrimitive + return + + def getClosestStartVelocity(self, initial_velocity): + """ + get the velocity among start states that is closest to the given initial velocity + """ + min_error = float('inf') + min_idx = 0 + + for i in range(len(self.Primitives)): + primitive = self.Primitives[i] + + error_velocity = abs(initial_velocity - primitive.startState.velocity) + if error_velocity < min_error: + min_error = error_velocity + min_idx = i + + return self.Primitives[min_idx].startState.velocity + + def setVehicleTypeIdPrimitives(self): + """ + assign vehicle type id to all primitives + """ + for primitive in self.Primitives: + primitive.veh_type_id = self.veh_type_id + diff --git a/motionAutomata/Automata/MotionPlanner.py b/GSMP/motion_automata/automata/MotionPlanner.py similarity index 75% rename from motionAutomata/Automata/MotionPlanner.py rename to GSMP/motion_automata/automata/MotionPlanner.py index bbf88939be5a475b62d029d9ccbffc90a1262988..4f345bc4f123fe9129795ec6ba10d172cacad7b2 100644 --- a/motionAutomata/Automata/MotionPlanner.py +++ b/GSMP/motion_automata/automata/MotionPlanner.py @@ -1,99 +1,120 @@ from commonroad_cc.collision_detection.pycrcc_collision_dispatch import create_collision_checker, create_collision_object -from commonroad.planning.planning_problem import PlanningProblemSet, PlanningProblem from commonroad.scenario.obstacle import StaticObstacle, ObstacleType, Obstacle from commonroad.scenario.trajectory import State as StateTupleFactory from commonroad.scenario.trajectory import State from commonroad.prediction.prediction import TrajectoryPrediction -from commonroad.visualization.draw_dispatch_cr import draw_object from commonroad.geometry.shape import Polygon, ShapeGroup, Circle -from commonroad.common.util import Interval, AngleInterval -from commonroad.scenario.lanelet import LaneletNetwork, Lanelet +from commonroad.common.util import Interval +from commonroad.scenario.lanelet import Lanelet from commonroad.scenario.trajectory import Trajectory -from commonroad.planning.goal import GoalRegion -from commonroad.geometry.shape import Rectangle -from Automata.States import StartState, FinalState -from Automata.MotionAutomata import MotionAutomata, MotionPrimitive -import time +from automata.MotionAutomata import MotionPrimitive import numpy as np import math import construction import heapq from typing import * + class MotionPlanner: - def __init__(self, scenario, planningProblem, automata, state_tuple, shapeEgoVehicle): + def __init__(self, scenario, planningProblem, automata): + # store input parameters self.scenario = scenario self.planningProblem = planningProblem self.automata = automata - self.state_tuple = state_tuple - self.frontier = PriorityQueue() + self.egoShape = automata.egoShape + + # create necessary attributes + self.lanelet_network = self.scenario.lanelet_network + self.priority_queue = PriorityQueue() self.obstacles = self.scenario.obstacles self.initial_state = self.planningProblem.initial_state - self.egoShape = shapeEgoVehicle + + # remove unneeded attributes of initial state if hasattr(self.initial_state, 'yaw_rate'): - del(self.initial_state.yaw_rate) + del self.initial_state.yaw_rate + if hasattr(self.initial_state, 'slip_angle'): - del(self.initial_state.slip_angle) - self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.initial_state.position])[0] - if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.center])[0] - elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] - self.planningProblem.goal.state_list[0].position.center = self.planningProblem.goal.state_list[0].position.shapes[0].center - self.initial_distance = distance(planningProblem.initial_state.position, planningProblem.goal.state_list[0].position.center) - self.lanelet_network = self.scenario.lanelet_network - self.lanelet_cost = {} - for lanelet_id in self.lanelet_network._lanelets.keys(): - self.lanelet_cost[lanelet_id] = -1 - for goal_lanelet in self.goalLanelet_ids: - self.lanelet_cost[goal_lanelet] = 0 - for goal_lanelet in self.goalLanelet_ids: - visited_lanelets = [] - self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet), 1, visited_lanelets) + del self.initial_state.slip_angle + # get lanelet id of the starting lanelet (of initial state) + self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.initial_state.position])[0] - build = ['section_triangles', 'triangulation'] - boundary = construction.construct(self.scenario, build, [], []) - road_boundary_shape_list = list() - for r in boundary['triangulation'].unpack(): - initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) - p = Polygon(np.array(r.vertices())) - road_boundary_shape_list.append(p) - road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) - self.collisionChecker = create_collision_checker(self.scenario) - self.collisionChecker.add_collision_object(create_collision_object(road_bound)) + # get lanelet id of the ending lanelet (of goal state),this depends on type of goal state + if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.center])[0] + elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] + self.planningProblem.goal.state_list[0].position.center = \ + self.planningProblem.goal.state_list[0].position.shapes[0].center + + # set specifications from given goal state if hasattr(self.planningProblem.goal.state_list[0], 'time_step'): self.desired_time = self.planningProblem.goal.state_list[0].time_step else: self.desired_time = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'velocity'): self.desired_velocity = self.planningProblem.goal.state_list[0].velocity else: self.desired_velocity = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'orientation'): self.desired_orientation = self.planningProblem.goal.state_list[0].orientation else: self.desired_orientation = Interval(-math.pi, math.pi) + # create necessary attributes + self.initial_distance = distance(planningProblem.initial_state.position, + planningProblem.goal.state_list[0].position.center) + + # set lanelet costs to -1, except goal lanelet + self.lanelet_cost = {} + for lanelet in scenario.lanelet_network.lanelets: + self.lanelet_cost[lanelet.lanelet_id] = -1 + + for goal_lanelet_id in self.goalLanelet_ids: + self.lanelet_cost[goal_lanelet_id] = 0 + + # calculate costs for lanelets, this is a recursive method + for goal_lanelet_id in self.goalLanelet_ids: + visited_lanelets = [] + self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet_id), 1, visited_lanelets) + + # construct commonroad boundaries and collision checker object + build = ['section_triangles', 'triangulation'] + boundary = construction.construct(self.scenario, build, [], []) + road_boundary_shape_list = list() + initial_state = None + for r in boundary['triangulation'].unpack(): + initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) + p = Polygon(np.array(r.vertices())) + road_boundary_shape_list.append(p) + road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, + obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) + self.collisionChecker = create_collision_checker(self.scenario) + self.collisionChecker.add_collision_object(create_collision_object(road_bound)) - def map_obstacles_to_lanelets(self, time_step : int) -> dict: + def map_obstacles_to_lanelets(self, time_step: int): """ - Finds all obstacles that are located in every lanelet at time step t and returns a dictionary where obstacles are stored according to their lanelet ids. + Find all obstacles that are located in every lanelet at time step t and returns a dictionary where obstacles are stored according to lanelet id. - :param time_step: maps obstacles in this time step to the lanelet - + :param time_step: The time step in which the obstacle is in the current lanelet network. + :Return type: dict[lanelet_id] """ mapping = {} - for l in self.lanelet_network._lanelets.values(): + for lanelet in self.lanelet_network.lanelets: # map obstacles to current lanelet - mapped_objs = self.get_obstacles(l, time_step) + mapped_objs = self.get_obstacles(lanelet, time_step) # check if mapping is not empty if len(mapped_objs) > 0: - mapping[l.lanelet_id] = mapped_objs + mapping[lanelet.lanelet_id] = mapped_objs return mapping - def get_obstacles(self, laneletObj: Lanelet, time_step : int) -> List[Obstacle]: + def get_obstacles(self, laneletObj: Lanelet, time_step: int) -> List[Obstacle]: """ Returns the subset of obstacles, which are located in the given lanelet. @@ -121,7 +142,7 @@ class MotionPlanner: else: vertices.append(sh.vertices) else: - # distinguish between type of shape (circle has no vertices) + # distinguish between type of shape (circle has no vertices) if isinstance(o_shape, Circle): vertices = o_shape.center else: @@ -132,37 +153,40 @@ class MotionPlanner: res.append(o) return res - def calc_lanelet_cost(self, curLanelet: Lanelet, dist: int, visited_lanelets: List[int]): """ Calculates distances of all lanelets which can be reached through recursive adjacency/predecessor relationship by the current lanelet. This is a recursive implementation. - :param curLanelet: the current lanelet object (often set to the goal lanelet) - :param dist: the initial distance between 2 adjacent lanelets (often set to 1). This value will increase recursively during the execution of this function. - :param visited_lanelets: list of visited lanelet ids. In the iterations, visited lanelets will not be considered. This value changes during the recursive implementation. + :param curLanelet: the current lanelet object (Often set to the goal lanelet). + :param dist: the initial distance between 2 adjacent lanelets (Often set to 1). This value will increase recursively during the execution of this function. + :param visited_lanelets: list of visited lanelet id. In the iterations, visited lanelets will not be considered. This value changes during the recursive implementation. The calculated costs will be stored in dictionary self.lanelet_cost[Lanelet]. """ if curLanelet.lanelet_id in visited_lanelets: return - visited_lanelets.append(curLanelet.lanelet_id) - if curLanelet._predecessor is not None: - for pred in curLanelet._predecessor: + else: + visited_lanelets.append(curLanelet.lanelet_id) + + if curLanelet.predecessor is not None: + for pred in curLanelet.predecessor: if self.lanelet_cost[pred] == -1 or self.lanelet_cost[pred] > dist: self.lanelet_cost[pred] = dist - for pred in curLanelet._predecessor: - self.calc_lanelet_cost(self.lanelet_network._lanelets[pred], dist+1, visited_lanelets) - if curLanelet._adj_left is not None and curLanelet._adj_left_same_direction == True: - if self.lanelet_cost[curLanelet._adj_left] == -1 or self.lanelet_cost[curLanelet._adj_left] > dist: - self.lanelet_cost[curLanelet._adj_left] = dist - self.calc_lanelet_cost(self.lanelet_network._lanelets[curLanelet._adj_left], dist+1, visited_lanelets) - if curLanelet.adj_right is not None and curLanelet.adj_right_same_direction == True: + + for pred in curLanelet.predecessor: + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(pred), dist + 1, visited_lanelets) + + if curLanelet.adj_left is not None and curLanelet.adj_left_same_direction: + if self.lanelet_cost[curLanelet.adj_left] == -1 or self.lanelet_cost[curLanelet.adj_left] > dist: + self.lanelet_cost[curLanelet.adj_left] = dist + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(curLanelet.adj_left), dist + 1, visited_lanelets) + + if curLanelet.adj_right is not None and curLanelet.adj_right_same_direction: if self.lanelet_cost[curLanelet.adj_right] == -1 or self.lanelet_cost[curLanelet.adj_right] > dist: self.lanelet_cost[curLanelet.adj_right] = dist - self.calc_lanelet_cost(self.lanelet_network._lanelets[curLanelet.adj_right], dist+1, visited_lanelets) + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(curLanelet.adj_right), dist + 1, visited_lanelets) - def calc_lanelet_orientation(self, lanelet_id: int, pos: np.ndarray) -> float: """ Returns lanelet orientation (angle in radian, counter-clockwise defined) at the given position and lanelet id. @@ -187,7 +211,7 @@ class MotionPlanner: goalPos = self.planningProblem.goal.state_list[0].position.center return math.atan2(goalPos[1] - curPos[1], goalPos[0] - curPos[0]) - def lanelets_of_position(self, lanelets: List[int], state: State, diff:float = math.pi/5) -> List[Lanelet]: + def lanelets_of_position(self, lanelets: List[int], state: State, diff: float = math.pi/5) -> List[int]: """ Returns all lanelets, whose angle to the orientation of the input state are smaller than pi/5. @@ -242,43 +266,44 @@ class MotionPlanner: """ Returns true if the the final lanelet is adjacent to the start lanelet. - :param start_lanelet_id: id of the first lanelet (start lanelet) - :param final_lanelet_id: id of the second lanelet (final lanelet) - + :param start_lanelet_id: id of the first lanelet (start lanelet). + :param final_lanelet_id: id of the second lanelet (final lanelet). + """ laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(start_lanelet_id) - if laneletObj._adj_left is not None and laneletObj._adj_left_same_direction == True: - if laneletObj._adj_left == final_lanelet_id: - return True - if laneletObj._adj_right is not None and laneletObj._adj_right_same_direction == True: - if laneletObj._adj_right == final_lanelet_id: - return True + if laneletObj.adj_left is not None and laneletObj.adj_left_same_direction: + if laneletObj.adj_left == final_lanelet_id: + return True + + if laneletObj.adj_right is not None and laneletObj.adj_right_same_direction: + if laneletObj.adj_right == final_lanelet_id: + return True return False def is_successor(self, start_lanelet_id: int, final_lanelet_id: int) -> bool: """ - Returns true if the the final lanelet is a successor of the start lanelet. + Returns true if the the final lanelet is a succrssor of the start lanelet. + + :param start_lanelet_id: id of the first lanelet (start lanelet). + :param final_lanelet_id: id of the second lanelet (final lanelet). - :param start_lanelet_id: id of the first lanelet (start lanelet) - :param final_lanelet_id: id of the second lanelet (final lanelet) - Return type: bool """ laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(start_lanelet_id) - if laneletObj._successor is not None: - for suc in laneletObj._successor: + if laneletObj.successor is not None: + for suc in laneletObj.successor: if suc == final_lanelet_id: return True return False - def is_goal_in_lane(self, lanelet_id: int, traversed_lanelets = None) -> bool: + def is_goal_in_lane(self, lanelet_id: int, traversed_lanelets=None) -> bool: """ Returns true if the goal is in the given lanelet or any successor (including all successors of successors) of the given lanelet. - :param lanelet_id: the id of the given lanelet - :param traversed_lanelets: helper variable which stores potential path (a list of lanelet id) to goal lanelet. Default value is None. + :param lanelet_id: the id of the given lanelet. + :param traversed_lanelets: helper variable which stores potential path (a list of lanelet id) to goal lanelet. Initialized to None. """ if traversed_lanelets is None: @@ -291,15 +316,16 @@ class MotionPlanner: if lanelet_id in self.goalLanelet_ids: return True laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(lanelet_id) - if laneletObj._successor is not None: - for suc in laneletObj._successor: + if laneletObj.successor is not None: + for suc in laneletObj.successor: if self.lanelet_cost[suc] >= 0: reachable = self.is_goal_in_lane(suc, traversed_lanelets) if reachable: return True return reachable - def calc_time_cost(self, path: List[State]) -> int: + @staticmethod + def calc_time_cost(path: List[State]) -> int: """ Returns time cost (number of time steps) to perform the given path. @@ -327,7 +353,7 @@ class MotionPlanner: goalPos = self.planningProblem.goal.state_list[0].position.center return distance(curPos, goalPos, distance_type) - def calc_heuristic_lanelet(self, path: List[State]) -> Tuple[float, list, list]: + def calc_heuristic_lanelet(self, path: List[State]) -> Union[Tuple[None, None, None], Tuple[float, list, list]]: """ Calculates the distance between every individual state of the path and the centers of the path's corresponding lanelets and sum them up. @@ -339,15 +365,15 @@ class MotionPlanner: """ end_lanelet_id = None dist = 0 - start_lanelet_id = self.scenario.lanelet_network.find_lanelet_by_position([path[0].position])[0] # returns id of the start lanelet + start_lanelet_id = self.scenario.lanelet_network.find_lanelet_by_position([path[0].position])[0] # returns id of the start lanelet if not start_lanelet_id: return None, None, None for i in range(len(path)): lanelets_of_pathSegment = self.lanelets_of_position(self.scenario.lanelet_network.find_lanelet_by_position([path[i].position])[0], path[i]) if not lanelets_of_pathSegment: - return None, None, None #return none if path element is not in a lanelet with correct orientation + return None, None, None # return none if path element is not in a lanelet with correct orientation laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(lanelets_of_pathSegment[0]) - dist = dist + findDistanceToNearestPoint(laneletObj.center_vertices, path[i].position) # distance to center line + dist = dist + findDistanceToNearestPoint(laneletObj.center_vertices, path[i].position) # distance to center line end_lanelet_id = lanelets_of_pathSegment return dist, end_lanelet_id, start_lanelet_id @@ -363,10 +389,9 @@ class MotionPlanner: return True return False - def remove_states_behind_goal(self, path: List[State]) -> List[State]: """ - Removes all states that are behind the state which statisfies goal state conditions and returns the pruned path. + Removes all states that are behind the state which satisfies goal state conditions and returns the pruned path. :param path: the path to be pruned """ @@ -391,34 +416,37 @@ class MotionPlanner: # create a collision object using the trajectory prediction of the ego vehicle co = create_collision_object(traj_pred) - #check collision for motion primitive - if (self.collisionChecker.collide(co)): + # check collision for motion primitive + if self.collisionChecker.collide(co): return False return True - def translate_primitive_to_current_state(self, primitive: MotionPrimitive, currentPath: List[State]) -> List[State]: + @staticmethod + def translate_primitive_to_current_state(primitive: MotionPrimitive, path_current: List[State]) -> List[State]: """ Uses the trajectory defined in the given primitive, translates it towards the last state of current path and returns the list of new path. In the newly appended part (created through translation of the primitive) of the path, the position, orientation and time step are changed, but the velocity is not changed. Attention: The input primitive itself will not be changed after this operation. :param primitive: the primitive to be translated - :param currentPath: the path whose last state is the goal state for the translation + :param path_current: the path whose last state is the goal state for the translation """ - return primitive.appendTrajectoryToState(currentPath[-1]) + return primitive.appendTrajectoryToState(path_current[-1]) - def append_path(self, currentPath: List[State], newPath: List[State]) -> List[State]: + @staticmethod + def append_path(path_current: List[State], newPath: List[State]) -> List[State]: """ Appends a new path to the current path and returns the whole path. - :param currentPath: current path which is to be extended + :param path_current: current path which is to be extended :param newPath: new path which is going to be added to the current path """ - path = currentPath[:] + path = path_current[:] path.extend(newPath) return path - def get_successor_primitives(self, cur_primitive: MotionPrimitive) -> List[MotionPrimitive]: + @staticmethod + def get_successor_primitives(cur_primitive: MotionPrimitive) -> List[MotionPrimitive]: """ Returns all possible successor primitives of the current primitive. @@ -426,49 +454,15 @@ class MotionPlanner: """ return cur_primitive.Successors - # Define your own heuristic cost function here. def calc_heuristic_cost(self, path: List[State], curPos: State) -> float or int: - """ - Returns heuristic cost for the path. - You should define your own cost function here. - - :param path: the heuristic cost is calculated based on this path - :param curPos: current position/state of your path. Every state has the following variables: position, velocity, orientation, time_step - """ + # Define your own heuristic cost function here. cost = 0 return cost - # Implement your search algorithm here. - def search_alg(self, startSuccessor: List[MotionPrimitive], maxTreeDepth: int, status: dict) -> Tuple[List[State], List[MotionPrimitive]]: - """ - Returns the path and the used primitives as a tuple. - - :param startSuccessor: all possible primitives for the start state - :param maxTreeDepth: maximum number of concatenated primitives - :param status: helper values including 'cost_so_far', 'time_step', 'orientation', 'velocity', which are used for the visualization in the jupyter notebook - + def search_alg(self, list_successors_start_state: List[MotionPrimitive], max_tree_depth: int, dict_status = None): # -> Tuple(List[State], List[MotionPrimitive]): + # Implement your search algorithm here. - """ - - ##print("Implement your own search algorithm") - - # List of states. Every state has the following variables: .position, .velocity, .orientation, .time_step - path = [self.initial_state] - - primitives = [] # list of used primitives - - total_cost = 0 - tree_depth = 0 - - - - # update status for jupyter notebook visualization - stat = {} - stat['cost_so_far'] = total_cost - stat['currentPath'] = path - status.value = stat - - return (path, primitives) + pass class PriorityQueue: @@ -500,11 +494,12 @@ class PriorityQueue: return None return heapq.heappop(self.elements)[2] + def findClosestVertex(centerVertices: np.ndarray, pos: np.ndarray) -> int: """ Return the index of the closest center vertice to the given position. - :param center_vertices: the vertices of the center line of the Lanelet described as a polyline [[x0,x1,...,xn],[y0,y1,...,yn]] + :param centerVertices: the vertices of the center line of the Lanelet described as a polyline [[x0,x1,...,xn],[y0,y1,...,yn]] :param pos: the closest vertex to this position will be found """ @@ -514,6 +509,7 @@ def findClosestVertex(centerVertices: np.ndarray, pos: np.ndarray) -> int: distances.append(distance(vertex, pos, 0)) return distances.index(min(distances)) + def calcAngleOfPosition(centerVertices: np.ndarray, pos: np.ndarray) -> float: """ Returns the angle (in world coordinate, radian) of the line defined by 2 nearest lanelet center vertices to the given position. @@ -526,10 +522,11 @@ def calcAngleOfPosition(centerVertices: np.ndarray, pos: np.ndarray) -> float: index_closestVert = index_closestVert - 1 return math.atan2(centerVertices[index_closestVert+1][1] - centerVertices[index_closestVert][1], centerVertices[index_closestVert+1][0] - centerVertices[index_closestVert][0]) + def distToClosestPointOnLine(vertexA: np.ndarray, vertexB: np.ndarray, pos: np.ndarray): """ Returns the distance of the given position to a line segment (e.g. the nearest lanelet center line segment to the given position). - + :param pos: :param vertexA: the start point of the line segment :param vertexB: the end point of the line segment @@ -547,6 +544,7 @@ def distToClosestPointOnLine(vertexA: np.ndarray, vertexB: np.ndarray, pos: np.n newVertex[1] = vertexA[1] + (vertexB[1] - vertexA[1])*s return distance(newVertex, pos, 0) + def findDistanceToNearestPoint(centerVertices: np.ndarray, pos: np.ndarray): """ Returns the closest euclidean distance to a polyline (e.g. defined by lanelet center vertices) according to the given position. @@ -558,12 +556,11 @@ def findDistanceToNearestPoint(centerVertices: np.ndarray, pos: np.ndarray): for vertex in centerVertices: distances.append(distance(vertex, pos, 0)) index_closestVert = distances.index(min(distances)) - dist1 = 0 - dist2 = 0 if (index_closestVert + 1) < len(centerVertices): dist1 = distToClosestPointOnLine(centerVertices[index_closestVert], centerVertices[index_closestVert+1], pos) else: dist1 = distance(centerVertices[index_closestVert], pos, 0) + if index_closestVert > 0: dist2 = distToClosestPointOnLine(centerVertices[index_closestVert-1], centerVertices[index_closestVert], pos) else: @@ -571,6 +568,7 @@ def findDistanceToNearestPoint(centerVertices: np.ndarray, pos: np.ndarray): return min(dist1, dist2) + def calc_travelled_distance(path: List[State]) -> float: """ Returns the travelled distance of the given path. @@ -583,6 +581,7 @@ def calc_travelled_distance(path: List[State]) -> float: dist = dist + distance(path[i].position, path[i+1].position) return dist + def euclideanDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the euclidean distance between 2 points. @@ -592,6 +591,7 @@ def euclideanDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return np.sqrt((pos1[0] - pos2[0]) * (pos1[0] - pos2[0]) + (pos1[1] - pos2[1]) * (pos1[1] - pos2[1])) + def manhattanDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the manhattan distance between 2 points. @@ -601,6 +601,7 @@ def manhattanDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return abs(pos1[0] - pos2[0]) + abs(pos1[1] - pos2[1]) + def chebyshevDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the chebyshev distance between 2 points. @@ -610,6 +611,7 @@ def chebyshevDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return max(abs(pos1[0] - pos2[0]), abs(pos1[1] - pos2[1])) + def sumOfSquaredDifference(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the squared euclidean distance between 2 points. @@ -619,6 +621,7 @@ def sumOfSquaredDifference(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return (pos1[0] - pos2[0])**2 + (pos1[1] - pos2[1])**2 + def meanAbsoluteError(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns a half of the manhattan distance between 2 points. @@ -628,6 +631,7 @@ def meanAbsoluteError(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return 0.5*(abs(pos1[0] - pos2[0]) + abs(pos1[1] - pos2[1])) + def meanSquaredError(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the mean of squared difference between 2 points. @@ -637,6 +641,7 @@ def meanSquaredError(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return 0.5*((pos1[0] - pos2[0])**2 + (pos1[1] - pos2[1])**2) + def canberraDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the canberra distance between 2 points. @@ -646,6 +651,7 @@ def canberraDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return abs(pos1[0] - pos2[0])/(abs(pos1[0]) + abs(pos2[0])) + abs(pos1[1] - pos2[1])/(abs(pos1[1]) + abs(pos2[1])) + def cosineDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ Returns the cosine distance between 2 points. @@ -655,46 +661,40 @@ def cosineDistance(pos1: np.ndarray, pos2: np.ndarray) -> float: """ return 1 - (pos1[0] * pos2[0] + pos1[1] * pos2[1])/(np.sqrt(pos1[0]**2 + pos2[0]**2) * np.sqrt(pos1[1]**2 + pos2[1]**2)) -def distance(pos1: np.ndarray, pos2: np.ndarray, type=0) -> float: + +def distance(pos1: np.ndarray, pos2: np.ndarray, distance_type=0) -> float: """ Returns the distance between 2 points, the type is specified by 'type'. :param pos1: the first point :param pos2: the second point - - type: 0 means euclideanDistance, - - 1 means manhattanDistance, - - 2 means chebyshevDistance, - - 3 means sumOfSquaredDifference, - - 4 means meanAbsoluteError, - - 5 means meanSquaredError, - - 6 means canberraDistance, - - 7 means cosineDistance. - """ - if (type == 0): + :param distance_type: specifies which kind of distance is used: + 1: manhattanDistance, + 2: chebyshevDistance, + 3: sumOfSquaredDifference, + 4: meanAbsoluteError, + 5: meanSquaredError, + 6: canberraDistance, + 7: cosineDistance. + """ + if distance_type == 0: return euclideanDistance(pos1, pos2) - elif (type == 1): + elif distance_type == 1: return manhattanDistance(pos1, pos2) - elif (type == 2): + elif distance_type == 2: return chebyshevDistance(pos1, pos2) - elif (type == 3): + elif distance_type == 3: return sumOfSquaredDifference(pos1, pos2) - elif (type == 4): + elif distance_type == 4: return meanAbsoluteError(pos1, pos2) - elif (type == 5): + elif distance_type == 5: return meanSquaredError(pos1, pos2) - elif (type == 6): + elif distance_type == 6: return canberraDistance(pos1, pos2) - elif (type == 7): + elif distance_type == 7: return cosineDistance(pos1, pos2) - return + return math.inf + def curvature_of_polyline(polyline: np.ndarray) -> float: """ @@ -712,6 +712,7 @@ def curvature_of_polyline(polyline: np.ndarray) -> float: curvature = curvature + abs(elem) return curvature + def orientation_diff(orientation_1: float, orientation_2: float) -> float: """ Returns the orientation difference between 2 orientations in radians. @@ -721,6 +722,7 @@ def orientation_diff(orientation_1: float, orientation_2: float) -> float: """ return math.pi - abs(abs(orientation_1 - orientation_2) - math.pi) + def length_of_polyline(polyline: np.ndarray): """ Returns the length of the polyline. diff --git a/motionAutomata/Automata/MotionPlanner_Astar.py b/GSMP/motion_automata/automata/MotionPlanner_Astar.py similarity index 77% rename from motionAutomata/Automata/MotionPlanner_Astar.py rename to GSMP/motion_automata/automata/MotionPlanner_Astar.py index fc52cf7e4b3653565e762af1b81e4070eb73bc69..962b12c010522b3a9f102fcbcd87d5c7fa147ae9 100644 --- a/motionAutomata/Automata/MotionPlanner_Astar.py +++ b/GSMP/motion_automata/automata/MotionPlanner_Astar.py @@ -1,84 +1,108 @@ from commonroad_cc.collision_detection.pycrcc_collision_dispatch import create_collision_checker, create_collision_object -from commonroad.planning.planning_problem import PlanningProblemSet, PlanningProblem from commonroad.scenario.obstacle import StaticObstacle, ObstacleType, Obstacle from commonroad.scenario.trajectory import State as StateTupleFactory from commonroad.scenario.trajectory import State from commonroad.prediction.prediction import TrajectoryPrediction -from commonroad.visualization.draw_dispatch_cr import draw_object from commonroad.geometry.shape import Polygon, ShapeGroup, Circle -from commonroad.common.util import Interval, AngleInterval +from commonroad.common.util import Interval from commonroad.scenario.lanelet import LaneletNetwork, Lanelet from commonroad.scenario.trajectory import Trajectory -from commonroad.planning.goal import GoalRegion -from commonroad.geometry.shape import Rectangle -from Automata.States import StartState, FinalState -from Automata.MotionAutomata import MotionAutomata, MotionPrimitive -import time +from automata.MotionAutomata import MotionPrimitive import numpy as np import math import construction import heapq from typing import * import warnings +import copy + class MotionPlanner: - def __init__(self, scenario, planningProblem, automata, state_tuple, shapeEgoVehicle): + def __init__(self, scenario, planningProblem, automata): + # store input parameters self.scenario = scenario self.planningProblem = planningProblem self.automata = automata - self.state_tuple = state_tuple - self.frontier = PriorityQueue() + self.egoShape = automata.egoShape + + # create necessary attributes + self.lanelet_network = self.scenario.lanelet_network + self.priority_queue = PriorityQueue() self.obstacles = self.scenario.obstacles self.initial_state = self.planningProblem.initial_state - self.egoShape = shapeEgoVehicle + + # remove unneeded attributes of initial state if hasattr(self.initial_state, 'yaw_rate'): - del(self.initial_state.yaw_rate) + del self.initial_state.yaw_rate + if hasattr(self.initial_state, 'slip_angle'): - del(self.initial_state.slip_angle) - self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.initial_state.position])[0] - if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.center])[0] - elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] - self.planningProblem.goal.state_list[0].position.center = self.planningProblem.goal.state_list[0].position.shapes[0].center - self.initial_distance = distance(planningProblem.initial_state.position, planningProblem.goal.state_list[0].position.center) - self.lanelet_network = self.scenario.lanelet_network - self.lanelet_cost = {} - for lanelet_id in self.lanelet_network._lanelets.keys(): - self.lanelet_cost[lanelet_id] = -1 - for goal_lanelet in self.goalLanelet_ids: - self.lanelet_cost[goal_lanelet] = 0 - for goal_lanelet in self.goalLanelet_ids: - visited_lanelets = [] - self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet), 1, visited_lanelets) + del self.initial_state.slip_angle + # get lanelet id of the starting lanelet (of initial state) + self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.initial_state.position])[0] - build = ['section_triangles', 'triangulation'] - boundary = construction.construct(self.scenario, build, [], []) - road_boundary_shape_list = list() - for r in boundary['triangulation'].unpack(): - initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) - p = Polygon(np.array(r.vertices())) - road_boundary_shape_list.append(p) - road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) - self.collisionChecker = create_collision_checker(self.scenario) - self.collisionChecker.add_collision_object(create_collision_object(road_bound)) + # get lanelet id of the ending lanelet (of goal state),this depends on type of goal state + if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.center])[0] + + elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] + self.planningProblem.goal.state_list[0].position.center = \ + self.planningProblem.goal.state_list[0].position.shapes[0].center + # set specifications from given goal state if hasattr(self.planningProblem.goal.state_list[0], 'time_step'): self.desired_time = self.planningProblem.goal.state_list[0].time_step else: self.desired_time = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'velocity'): self.desired_velocity = self.planningProblem.goal.state_list[0].velocity else: self.desired_velocity = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'orientation'): self.desired_orientation = self.planningProblem.goal.state_list[0].orientation else: self.desired_orientation = Interval(-math.pi, math.pi) + # create necessary attributes + self.initial_distance = distance(planningProblem.initial_state.position, + planningProblem.goal.state_list[0].position.center) + + # set lanelet costs to -1, except goal lanelet + self.lanelet_cost = {} + for lanelet in scenario.lanelet_network.lanelets: + self.lanelet_cost[lanelet.lanelet_id] = -1 + + for goal_lanelet_id in self.goalLanelet_ids: + self.lanelet_cost[goal_lanelet_id] = 0 + + # calculate costs for lanelets, this is a recursive method + for goal_lanelet_id in self.goalLanelet_ids: + visited_lanelets = [] + self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet_id), 1, visited_lanelets) + + # construct commonroad boundaries and collision checker object + build = ['section_triangles', 'triangulation'] + boundary = construction.construct(self.scenario, build, [], []) + road_boundary_shape_list = list() + initial_state = None + for r in boundary['triangulation'].unpack(): + initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) + p = Polygon(np.array(r.vertices())) + road_boundary_shape_list.append(p) + road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, + obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) + self.collisionChecker = create_collision_checker(self.scenario) + self.collisionChecker.add_collision_object(create_collision_object(road_bound)) + # Create lanes from lanelet network - def merge_lanelets(self, lanelet1: Lanelet, lanelet2: Lanelet) -> Lanelet: + @staticmethod + def merge_lanelets(lanelet1: Lanelet, lanelet2: Lanelet) -> Lanelet: """ Merges two lanelets which are in predecessor-successor relation and returns the merged lanelet (predecessor => successor). @@ -118,7 +142,8 @@ class MotionPlanner: return Lanelet(left_vertices, center_vertices, right_vertices, lanelet_id, predecessor=predecessor, successor=successor) - def all_lanelets_by_merging_successors_from_lanelet(self, lanelet: Lanelet, network: LaneletNetwork) -> list: + @staticmethod + def all_lanelets_by_merging_successors_from_lanelet(lanelet: Lanelet, network: LaneletNetwork) -> list: """ Computes all reachable and merged lanelets starting from a provided lanelet :param lanelet: The lanelet to start from @@ -138,7 +163,7 @@ class MotionPlanner: merge_jobs = list() # add initial jobs for s in lanelet.successor: - #print("successor lanelet id", s) + # print("successor lanelet id", s) merge_jobs.append([lanelet,network.find_lanelet_by_id(s)]) visited_lanelets_id.append(s) @@ -304,7 +329,7 @@ class MotionPlanner: goalPos = self.planningProblem.goal.state_list[0].position.center return math.atan2(goalPos[1] - curPos[1], goalPos[0] - curPos[0]) - def lanelets_of_position(self, lanelets: List[int], state: State, diff=math.pi/5) -> List[Lanelet]: + def lanelets_of_position(self, lanelets: List[int], state: State, diff=math.pi/5) -> List[int]: """ Returns all lanelets, the angle between which and the orientation of the input state is smaller than pi/5. @@ -513,25 +538,25 @@ class MotionPlanner: return False return True - def translate_primitive_to_current_state(self, primitive: MotionPrimitive, currentPath: List[State]) -> List[State]: + def translate_primitive_to_current_state(self, primitive: MotionPrimitive, path_current: List[State]) -> List[State]: """ Uses the value of the given primitive, translate them towards the last state of current path and returns the list of new path. In the newly appended part of the path, the position, orientation and time step are changed, but the velocity is not changed. Attention: The input primitive itself will not be changed after this operation. - :param prmmitive: the primitive to be translated. - :param currentPath: the path whose last state is the reference state for the translation. + :param primitive: the primitive to be translated. + :param path_current: the path whose last state is the reference state for the translation. """ - return primitive.appendTrajectoryToState(currentPath[-1]) + return primitive.appendTrajectoryToState(path_current[-1]) - def append_path(self, currentPath: List[State], newPath: List[State]) -> List[State]: + def append_path(self, path_current: List[State], newPath: List[State]) -> List[State]: """ Appends a new path to the current path and returns the whole path. - :param currentPath: current path which is to be extended. + :param path_current: current path which is to be extended. :param newPath: new path which is going to be added to the current path. """ - path = currentPath[:] + path = path_current[:] path.extend(newPath) return path @@ -543,15 +568,19 @@ class MotionPlanner: """ return cur_primitive.Successors - # Define your own heuristic cost function here. def calc_heuristic_cost(self, path: List[State], curPos: State): """ Returns heuristic cost for the path. You should define your own cost function here. - :param path: The heuristic cost is calculated based on this path. - :param curPos: Current position/state of your path. Every state has the following variables: position, velocity, orientation, time_step + :param path: The path for which you want to calculate the cost + :param curPos: Last state of your current path. Every state has the following variables: position, velocity, orientation, time_step """ + + # *** below is just a sample code from a random previous student, + # *** you are free to come up with your own ideas on how to compute the heuristic cost + # sample code 1 + # Dist is distance to lanelet center (dist, lanelet_id, start_lanelet) = self.calc_heuristic_lanelet(path) # TODO: lanelet_id here is actually end_lanelet_id @@ -559,10 +588,11 @@ class MotionPlanner: heuristic_cost = np.inf return heuristic_cost - dist_to_closest_obst = self.dist_to_closest_obstacle(int(lanelet_id[0]), curPos[-1].position, int(curPos[-1].time_step)) - #print("dist to closest obstacle", dist_to_closest_obst) - num_obstacels_in_lanelet = self.num_obstacles_in_lanelet_at_time_step(int(curPos[-1].time_step), int(lanelet_id[0])) - #print("num of obsatcles in lane", num_obstacels_in_lanelet) + dist_to_closest_obst = self.dist_to_closest_obstacle(int(lanelet_id[0]), curPos.position, int(curPos.time_step)) + # print("dist to closest obstacle", dist_to_closest_obst) + + num_obstacels_in_lanelet = self.num_obstacles_in_lanelet_at_time_step(int(curPos.time_step), int(lanelet_id[0])) + # print("num of obsatcles in lane", num_obstacels_in_lanelet) w = 1 if lanelet_id is not None: @@ -580,111 +610,149 @@ class MotionPlanner: efficiency = 1.7-0.2*self.calc_path_efficiency(path) # check if the orientation is close to the final orientation - angle = abs(self.calc_angle_to_goal(curPos[-1])) + angle = abs(self.calc_angle_to_goal(curPos)) orientationDiff = 1 if lanelet_id is not None: - orientation_1 = self.calc_lanelet_orientation(lanelet_id, curPos[-1].position) + orientation_1 = self.calc_lanelet_orientation(lanelet_id, curPos.position) orientation_2 = self.desired_orientation # Median of angle orientation_2_med = ((orientation_2.start + orientation_2.end) / 2) orientationDiff = 100 * orientation_diff(orientation_1, orientation_2_med) - heuristic_dist = self.calc_heuristic_distance(curPos[-1]) - heuristic_cost = heuristic_dist * w * angle * efficiency * 15 * orientationDiff * dist #* orientation - #print("heuristic factor" ,w * angle * efficiency * 10 * orientationDiff * dist) + heuristic_dist = self.calc_heuristic_distance(curPos) + heuristic_cost = heuristic_dist * w * angle * efficiency * 15 * orientationDiff * dist # * orientation + + heuristic_cost = heuristic_dist * 20 + angle * 10 + # print("heuristic factor" ,w * angle * efficiency * 10 * orientationDiff * dist) return heuristic_cost - # Implement your search algorithm here. - def search_alg(self, startSuccessor: List[MotionPrimitive], maxTreeDepth: int, status) -> (List[State], List[MotionPrimitive]): + def search_alg(self, list_successors_start_state: List[MotionPrimitive], max_tree_depth: int, dict_status = None) -> (List[State], List[MotionPrimitive]): """ Returns the path and the used primitives - :param startSuccessor: All possible primitives for the start state - :param maxTreeDepth: Maximum number of concatenated primitives - :param status: Used for the visualization in the jupyter notebook + :param list_successors_start_state: All possible primitives for the start state + :param max_tree_depth: Maximum number of concatenated primitives + :param dict_status: Used for the visualization in the jupyter notebook """ - ##print("Implement your own search algorithm") - # List of states. Every state has the following variables: .position, .velocity, .orientation, .time_step + # Here an A* algorithm is demonstrated. # + + # Every state has the following attributes: .position, .velocity, .orientation, .time_step + # For more information please refer to the commonroad-io tutorial + cost_g = 0 path = [self.initial_state] - primitives = [] # list of used primitives - total_cost = 0 tree_depth = 0 - - # Add the start primitives - next_primitive = startSuccessor - - # calculate first step - for num in range(len(next_primitive)): - - # Add primitives to start position - #Translates a motion primitive to current position. Note: All motion primitives start at position [0, 0] T . - pathNew = self.translate_primitive_to_current_state(next_primitive[num], path) - #path - current_path = self.append_path(path, pathNew) - #time cost if that primitive would be used - time_cost = self.calc_time_cost(current_path) - #cost so far if that primitive would be used - total_cost = calc_travelled_distance(current_path) - - #check if the new primitive leads to collisions - if self.check_collision_free(current_path): - # calculate heuristic if no collision is detected - heuristic_cost = self.calc_heuristic_cost(current_path, pathNew) - cost = heuristic_cost + total_cost - self.frontier.put((next_primitive[num], total_cost, current_path, heuristic_cost, time_cost), cost) - - stat = {} - stat['cost_so_far'] = total_cost - stat['currentPath'] = current_path - status.value = stat - - if self.reached_goal(current_path): - return (self.remove_states_behind_goal(current_path), [next_primitive[num]]) - - while not self.frontier.empty(): - - # Get most promising primitive - (old_primitive, cost_so_far, current_path, old_heuristic_cost, old_time_cost) = self.frontier.get() - - next_primitive = self.get_successor_primitives(old_primitive) - - for num in range(len(next_primitive)): - - #Translates a motion primitive to current position. Note: All motion primitives start at position [0, 0] T . - pathNew = self.translate_primitive_to_current_state(next_primitive[num], current_path) - #path - current_path_successor = self.append_path(current_path, pathNew) - - if self.reached_goal(current_path_successor): - return (self.remove_states_behind_goal(current_path_successor), [next_primitive[num]]) - - #time cost if that primitive would be used - time_cost = self.calc_time_cost(current_path_successor) - #cost so far if that primitive would be used - total_cost = calc_travelled_distance(current_path_successor) - - #check if the new primitive leads to collisions - if self.check_collision_free(current_path_successor): - # calculate heuristic if no collision is detected - heuristic_cost = self.calc_heuristic_cost(current_path_successor, pathNew) - cost = heuristic_cost + total_cost - - self.frontier.put((next_primitive[num], total_cost, current_path_successor, heuristic_cost, time_cost), cost) - - stat = {} - stat['cost_so_far'] = total_cost - stat['currentPath'] = current_path_successor - status.value = stat - - - return (self.remove_states_behind_goal(current_path_successor), [next_primitive[num]]) - - + path_appended = [self.initial_state] + list_primitives = [] + priority = 0 + + # if the goal state is reached by the current path + if self.reached_goal(path): + # return a pruned path and its corresponding primitives + return self.remove_states_behind_goal(path), list_primitives + + # inputs for PriorityQueue: (cost_g, : cumulative cost of the path so far + # path, : current path + # list_successors_primitive_last, : list of successors of the last primitive in the path + # tree_depth, : tree depth + # path_appended, : the path that is appened in this iteration + # list_primitives), : list of primitives of the current path + # priority : cost of the path / value to be sorted in the heap + + list_primitives_copied = copy.copy(list_primitives) + # add initial state into priority queue + self.priority_queue.put((cost_g, # : initial cost is 0 + path, # : initial path only contains the initial state + list_successors_start_state, # : the successors of the initial state + tree_depth, # : initial depth is 0 + path_appended, # : only initial state is added to the path + list_primitives_copied), # : no primitives add to the list yet + priority) # : initial priority is 0 + + # while the queue is not empty + while not self.priority_queue.empty(): + # get the item with lowest cost from the queue + # elements represented by _ are not used in the following + + (cost_g, path, list_successors_primitive_last, tree_depth, _, list_primitives) = self.priority_queue.get() + list_primitives_copied = copy.copy(list_primitives) + + status = {'cost_current': cost_g, + 'tree_depth': tree_depth, + 'path_current': path} + + if dict_status is not None: dict_status.value = status + + # check whether the tree depth exceeds the maximum allowed number + if tree_depth > max_tree_depth: + print("reached max tree depth") + + return None + else: + tree_depth += 1 + + # skip if the time step of the last state of path exceeds that of the goal state + if path[-1].time_step > self.desired_time.end: + continue + + # otherwise, expand all successors of the primitive + for i in range(len(list_successors_primitive_last)): + # get a primitive from the list of successors + primitive_next = list_successors_primitive_last[i] + + # add new primitves to the current path + # we attach the primitive to current path by translating the pritimive, and + # obtain a path containing the translated states + # Note: all motion primitives start at position [0, 0]^T + path_primitive_translated = self.translate_primitive_to_current_state(primitive_next, path) + + # skip if the time step of the last state of path exceeds that of goal state + if path_primitive_translated[0].time_step > self.desired_time.end: + continue + + # skip this translated path if it is not collision free + if not self.check_collision_free(path_primitive_translated): + continue + + # otherwise, calculated the cost associated with this path + # lower cost implies higher priority when expanding + # in A*, the final cost (f) = heuristic cost (h) + cumulative cost (g) + + cost_g_increment = calc_travelled_distance(path_primitive_translated) + cost_g = cost_g + cost_g_increment + cost_h = self.calc_heuristic_cost(path_primitive_translated, path[-1]) + cost_f = cost_h + cost_g + + # add primitive into the list of primitives + list_primitives_copied.append(primitive_next) + + # if the goal state is reached by the new path_primitive_translated + if self.reached_goal(path_primitive_translated): + # concacenate its predecessor and return result + path_new = path + path_primitive_translated + + # return a pruned path and its corresponding primitives + return self.remove_states_behind_goal(path_new), list_primitives_copied + + # get new path by concatenating current path and the path translated from the primitve + path_new = path + path_primitive_translated + + # push the new path with corresponding values into the priority queue + self.priority_queue.put( + (cost_g, + path_new, + self.get_successor_primitives(primitive_next), + tree_depth, + path_primitive_translated, + list_primitives_copied), + cost_f) + + # return None if no feasible path is found + return None class PriorityQueue: def __init__(self): diff --git a/motionAutomata/Automata/MotionPlanner_gbfs.py b/GSMP/motion_automata/automata/MotionPlanner_gbfs.py similarity index 55% rename from motionAutomata/Automata/MotionPlanner_gbfs.py rename to GSMP/motion_automata/automata/MotionPlanner_gbfs.py index 02a0a190d9276b2bdc71dd2fe08a384c2e1577cc..89193b425f42c28a009e7a9d10c9d321e48c60f4 100644 --- a/motionAutomata/Automata/MotionPlanner_gbfs.py +++ b/GSMP/motion_automata/automata/MotionPlanner_gbfs.py @@ -1,83 +1,112 @@ from commonroad_cc.collision_detection.pycrcc_collision_dispatch import create_collision_checker, create_collision_object -from commonroad.planning.planning_problem import PlanningProblemSet, PlanningProblem from commonroad.scenario.obstacle import StaticObstacle, ObstacleType, Obstacle from commonroad.scenario.trajectory import State as StateTupleFactory -from commonroad.scenario.trajectory import State +from commonroad.scenario.trajectory import State from commonroad.prediction.prediction import TrajectoryPrediction -from commonroad.visualization.draw_dispatch_cr import draw_object from commonroad.geometry.shape import Polygon, ShapeGroup, Circle -from commonroad.common.util import Interval, AngleInterval -from commonroad.scenario.lanelet import LaneletNetwork, Lanelet +from commonroad.common.util import Interval +from commonroad.scenario.lanelet import Lanelet from commonroad.scenario.trajectory import Trajectory -from commonroad.planning.goal import GoalRegion -from commonroad.geometry.shape import Rectangle -from Automata.States import StartState, FinalState -from Automata.MotionAutomata import MotionAutomata, MotionPrimitive -import time +from automata.MotionAutomata import MotionPrimitive import numpy as np import math import construction import heapq +import copy from typing import * + class MotionPlanner: - def __init__(self, scenario, planningProblem, automata, state_tuple, shapeEgoVehicle): + def __init__(self, scenario, planningProblem, automata): + # store input parameters self.scenario = scenario self.planningProblem = planningProblem self.automata = automata - self.state_tuple = state_tuple - self.frontier = PriorityQueue() + + self.egoShape = automata.egoShape + + # create necessary attributes + self.lanelet_network = self.scenario.lanelet_network + self.priority_queue = PriorityQueue() self.obstacles = self.scenario.obstacles self.initial_state = self.planningProblem.initial_state - self.egoShape = shapeEgoVehicle - if hasattr(self.initial_state, 'yaw_rate'): - del(self.initial_state.yaw_rate) - if hasattr(self.initial_state, 'slip_angle'): - del(self.initial_state.slip_angle) - self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.initial_state.position])[0] - if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.center])[0] - elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): - self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position([self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] - self.planningProblem.goal.state_list[0].position.center = self.planningProblem.goal.state_list[0].position.shapes[0].center - self.initial_distance = distance(planningProblem.initial_state.position, planningProblem.goal.state_list[0].position.center) - self.lanelet_network = self.scenario.lanelet_network - self.lanelet_cost = {} - for lanelet_id in self.lanelet_network._lanelets.keys(): - self.lanelet_cost[lanelet_id] = -1 - for goal_lanelet in self.goalLanelet_ids: - self.lanelet_cost[goal_lanelet] = 0 - for goal_lanelet in self.goalLanelet_ids: - visited_lanelets = [] - self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet), 1, visited_lanelets) - - build = ['section_triangles', 'triangulation'] - boundary = construction.construct(self.scenario, build, [], []) - road_boundary_shape_list = list() - for r in boundary['triangulation'].unpack(): - initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) - p = Polygon(np.array(r.vertices())) - road_boundary_shape_list.append(p) - road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) - self.collisionChecker = create_collision_checker(self.scenario) - self.collisionChecker.add_collision_object(create_collision_object(road_bound)) + # remove unneeded attributes of initial state + if hasattr(self.initial_state, 'yaw_rate'): + del self.initial_state.yaw_rate + if hasattr(self.initial_state, 'slip_angle'): + del self.initial_state.slip_angle + + # get lanelet id of the starting lanelet (of initial state) + self.startLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.initial_state.position])[0] + + self.goalLanelet_ids = None + # get lanelet id of the ending lanelet (of goal state),this depends on type of goal state + if hasattr(self.planningProblem.goal.state_list[0], 'position'): + if hasattr(self.planningProblem.goal.state_list[0].position, 'center'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.center])[0] + + elif hasattr(planningProblem.goal.state_list[0].position, 'shapes'): + self.goalLanelet_ids = self.scenario.lanelet_network.find_lanelet_by_position( + [self.planningProblem.goal.state_list[0].position.shapes[0].center])[0] + self.planningProblem.goal.state_list[0].position.center = \ + self.planningProblem.goal.state_list[0].position.shapes[0].center + + # set specifications from given goal state if hasattr(self.planningProblem.goal.state_list[0], 'time_step'): self.desired_time = self.planningProblem.goal.state_list[0].time_step else: self.desired_time = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'velocity'): self.desired_velocity = self.planningProblem.goal.state_list[0].velocity else: self.desired_velocity = Interval(0, np.inf) + if hasattr(self.planningProblem.goal.state_list[0], 'orientation'): self.desired_orientation = self.planningProblem.goal.state_list[0].orientation else: self.desired_orientation = Interval(-math.pi, math.pi) + # create necessary attributes + if hasattr(planningProblem.goal.state_list[0], 'position'): + self.initial_distance = distance(planningProblem.initial_state.position, + planningProblem.goal.state_list[0].position.center) + else: + self.initial_distance = 0 + + # set lanelet costs to -1, except goal lanelet + self.lanelet_cost = {} + for lanelet in scenario.lanelet_network.lanelets: + self.lanelet_cost[lanelet.lanelet_id] = -1 + + if self.goalLanelet_ids is not None: + for goal_lanelet_id in self.goalLanelet_ids: + self.lanelet_cost[goal_lanelet_id] = 0 + + # calculate costs for lanelets, this is a recursive method + for goal_lanelet_id in self.goalLanelet_ids: + visited_lanelets = [] + self.calc_lanelet_cost(self.scenario.lanelet_network.find_lanelet_by_id(goal_lanelet_id), 1, visited_lanelets) + + # construct commonroad boundaries and collision checker object + build = ['section_triangles', 'triangulation'] + boundary = construction.construct(self.scenario, build, [], []) + road_boundary_shape_list = list() + initial_state = None + for r in boundary['triangulation'].unpack(): + initial_state = StateTupleFactory(position=np.array([0, 0]), orientation=0.0, time_step=0) + p = Polygon(np.array(r.vertices())) + road_boundary_shape_list.append(p) + road_bound = StaticObstacle(obstacle_id=scenario.generate_object_id(), obstacle_type=ObstacleType.ROAD_BOUNDARY, + obstacle_shape=ShapeGroup(road_boundary_shape_list), initial_state=initial_state) + self.collisionChecker = create_collision_checker(self.scenario) + self.collisionChecker.add_collision_object(create_collision_object(road_bound)) - def map_obstacles_to_lanelets(self, time_step : int): + def map_obstacles_to_lanelets(self, time_step: int): """ Find all obstacles that are located in every lanelet at time step t and returns a dictionary where obstacles are stored according to lanelet id. @@ -85,15 +114,15 @@ class MotionPlanner: :Return type: dict[lanelet_id] """ mapping = {} - for l in self.lanelet_network._lanelets.values(): + for lanelet in self.lanelet_network.lanelets: # map obstacles to current lanelet - mapped_objs = self.get_obstacles(l, time_step) + mapped_objs = self.get_obstacles(lanelet, time_step) # check if mapping is not empty if len(mapped_objs) > 0: - mapping[l.lanelet_id] = mapped_objs + mapping[lanelet.lanelet_id] = mapped_objs return mapping - def get_obstacles(self, laneletObj: Lanelet, time_step : int) -> List[Obstacle]: + def get_obstacles(self, laneletObj: Lanelet, time_step: int) -> List[Obstacle]: """ Returns the subset of obstacles, which are located in the given lanelet. @@ -121,7 +150,7 @@ class MotionPlanner: else: vertices.append(sh.vertices) else: - # distinguish between type of shape (circle has no vertices) + # distinguish between type of shape (circle has no vertices) if isinstance(o_shape, Circle): vertices = o_shape.center else: @@ -132,37 +161,40 @@ class MotionPlanner: res.append(o) return res - def calc_lanelet_cost(self, curLanelet: Lanelet, dist: int, visited_lanelets: List[int]): """ Calculates distances of all lanelets which can be reached through recursive adjacency/predecessor relationship by the current lanelet. This is a recursive implementation. :param curLanelet: the current lanelet object (Often set to the goal lanelet). - :param dist: the initial distance between 2 adjacent lanelets (Often set to 1). This value will increase recursively durcing the execution of this function. + :param dist: the initial distance between 2 adjacent lanelets (Often set to 1). This value will increase recursively during the execution of this function. :param visited_lanelets: list of visited lanelet id. In the iterations, visited lanelets will not be considered. This value changes during the recursive implementation. The calculated costs will be stored in dictionary self.lanelet_cost[Lanelet]. """ if curLanelet.lanelet_id in visited_lanelets: return - visited_lanelets.append(curLanelet.lanelet_id) - if curLanelet._predecessor is not None: - for pred in curLanelet._predecessor: + else: + visited_lanelets.append(curLanelet.lanelet_id) + + if curLanelet.predecessor is not None: + for pred in curLanelet.predecessor: if self.lanelet_cost[pred] == -1 or self.lanelet_cost[pred] > dist: self.lanelet_cost[pred] = dist - for pred in curLanelet._predecessor: - self.calc_lanelet_cost(self.lanelet_network._lanelets[pred], dist+1, visited_lanelets) - if curLanelet._adj_left is not None and curLanelet._adj_left_same_direction == True: - if self.lanelet_cost[curLanelet._adj_left] == -1 or self.lanelet_cost[curLanelet._adj_left] > dist: - self.lanelet_cost[curLanelet._adj_left] = dist - self.calc_lanelet_cost(self.lanelet_network._lanelets[curLanelet._adj_left], dist+1, visited_lanelets) - if curLanelet.adj_right is not None and curLanelet.adj_right_same_direction == True: + + for pred in curLanelet.predecessor: + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(pred), dist + 1, visited_lanelets) + + if curLanelet.adj_left is not None and curLanelet.adj_left_same_direction: + if self.lanelet_cost[curLanelet.adj_left] == -1 or self.lanelet_cost[curLanelet.adj_left] > dist: + self.lanelet_cost[curLanelet.adj_left] = dist + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(curLanelet.adj_left), dist + 1, visited_lanelets) + + if curLanelet.adj_right is not None and curLanelet.adj_right_same_direction: if self.lanelet_cost[curLanelet.adj_right] == -1 or self.lanelet_cost[curLanelet.adj_right] > dist: self.lanelet_cost[curLanelet.adj_right] = dist - self.calc_lanelet_cost(self.lanelet_network._lanelets[curLanelet.adj_right], dist+1, visited_lanelets) + self.calc_lanelet_cost(self.lanelet_network.find_lanelet_by_id(curLanelet.adj_right), dist + 1, visited_lanelets) - def calc_lanelet_orientation(self, lanelet_id: int, pos: np.ndarray) -> float: """ Returns lanelet orientation (angle in radian, counter-clockwise defined) at the given position and lanelet id. @@ -184,10 +216,13 @@ class MotionPlanner: """ curPos = state.position - goalPos = self.planningProblem.goal.state_list[0].position.center - return math.atan2(goalPos[1] - curPos[1], goalPos[0] - curPos[0]) + if hasattr(self.planningProblem.goal.state_list[0], 'position'): + goalPos = self.planningProblem.goal.state_list[0].position.center + return math.atan2(goalPos[1] - curPos[1], goalPos[0] - curPos[0]) + else: + return 0 - def lanelets_of_position(self, lanelets: List[int], state: State, diff=math.pi/5) -> List[Lanelet]: + def lanelets_of_position(self, lanelets: List[int], state: State, diff=math.pi / 5) -> List[int]: """ Returns all lanelets, the angle between which and the orientation of the input state is smaller than pi/5. @@ -203,11 +238,13 @@ class MotionPlanner: laneletOrientationAtPosition = calcAngleOfPosition(laneletObj.center_vertices, state.position) if math.pi - abs(abs(laneletOrientationAtPosition - state.orientation) - math.pi) < diff: correctLanelets.append(laneletId) + while len(correctLanelets) > 0: - if self.lanelet_cost[correctLanelets[0]] == -1: + if self.lanelet_cost[correctLanelets[0]] == -1: correctLanelets.pop(0) else: break + return correctLanelets def dist_to_closest_obstacle(self, lanelet_id: int, pos: np.ndarray, time_step: int) -> float: @@ -235,7 +272,8 @@ class MotionPlanner: :param lanelet_id: id of the lanelet whose obstacles are considered. """ - obstacles_in_lanelet = self.get_obstacles(self.scenario.lanelet_network.find_lanelet_by_id(lanelet_id), time_step) + obstacles_in_lanelet = self.get_obstacles(self.scenario.lanelet_network.find_lanelet_by_id(lanelet_id), + time_step) return len(obstacles_in_lanelet) def is_adjacent(self, start_lanelet_id: int, final_lanelet_id: int) -> bool: @@ -248,12 +286,13 @@ class MotionPlanner: """ laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(start_lanelet_id) - if laneletObj._adj_left is not None and laneletObj._adj_left_same_direction == True: - if laneletObj._adj_left == final_lanelet_id: - return True - if laneletObj._adj_right is not None and laneletObj._adj_right_same_direction == True: - if laneletObj._adj_right == final_lanelet_id: - return True + if laneletObj.adj_left is not None and laneletObj.adj_left_same_direction: + if laneletObj.adj_left == final_lanelet_id: + return True + + if laneletObj.adj_right is not None and laneletObj.adj_right_same_direction: + if laneletObj.adj_right == final_lanelet_id: + return True return False def is_successor(self, start_lanelet_id: int, final_lanelet_id: int) -> bool: @@ -267,13 +306,13 @@ class MotionPlanner: """ laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(start_lanelet_id) - if laneletObj._successor is not None: - for suc in laneletObj._successor: + if laneletObj.successor is not None: + for suc in laneletObj.successor: if suc == final_lanelet_id: return True return False - def is_goal_in_lane(self, lanelet_id: int, traversed_lanelets = None) -> bool: + def is_goal_in_lane(self, lanelet_id: int, traversed_lanelets=None) -> bool: """ Returns true if the goal is in the given lanelet or any successor (including all successors of successors) of the given lanelet. @@ -291,15 +330,16 @@ class MotionPlanner: if lanelet_id in self.goalLanelet_ids: return True laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(lanelet_id) - if laneletObj._successor is not None: - for suc in laneletObj._successor: + if laneletObj.successor is not None: + for suc in laneletObj.successor: if self.lanelet_cost[suc] >= 0: reachable = self.is_goal_in_lane(suc, traversed_lanelets) if reachable: return True return reachable - def calc_time_cost(self, path: List[State]) -> int: + @staticmethod + def calc_time_cost(path: List[State]) -> int: """ Returns time cost (number of time steps) to perform the given path. @@ -313,21 +353,22 @@ class MotionPlanner: :param path: the path whose efficiency should be calculated. """ - return calc_travelled_distance(path)/self.calc_time_cost(path) + return calc_travelled_distance(path) / self.calc_time_cost(path) def calc_heuristic_distance(self, state: State, distance_type=0) -> float: """ Returns the heuristic distance between the current state and the goal state. :param state: the state, whose heuristic distance to the goal is calculated. - :param distance_type: 0: euclideanDistance, 1: manhattanDistance, 2: chebyshevDistance, 3: sumOfSquaredDifference, 4: meanAbsoluteError, 5: meanSquaredError, 6: canberraDistance, 7: cosineDistance + :param distance_type: 0: euclideanDistance, 1: manhattanDistance, 2: chebyshevDistance, 3: sumOfSquaredDifference, + 4: meanAbsoluteError, 5: meanSquaredError, 6: canberraDistance, 7: cosineDistance """ curPos = state.position goalPos = self.planningProblem.goal.state_list[0].position.center return distance(curPos, goalPos, distance_type) - - def calc_heuristic_lanelet(self, path: List[State]): + + def calc_heuristic_lanelet(self, path: List[State]): """ Calculated the distance between every individual state of the path and the centers of their corresponding lanelets and sum them up. @@ -339,17 +380,20 @@ class MotionPlanner: """ end_lanelet_id = None dist = 0 - start_lanelet_id = self.scenario.lanelet_network.find_lanelet_by_position([path[0].position])[0] # returns id of the start lanelet + start_lanelet_id = self.scenario.lanelet_network.find_lanelet_by_position([path[0].position])[ + 0] # returns id of the start lanelet if not start_lanelet_id: return None, None, None for i in range(len(path)): - lanelets_of_pathSegment = self.lanelets_of_position(self.scenario.lanelet_network.find_lanelet_by_position([path[i].position])[0], path[i]) + lanelets_of_pathSegment = self.lanelets_of_position( + self.scenario.lanelet_network.find_lanelet_by_position([path[i].position])[0], path[i]) if not lanelets_of_pathSegment: - return None, None, None #return none if path element is not in a lanelet with correct orientation + return None, None, None # return none if path element is not in a lanelet with correct orientation laneletObj = self.scenario.lanelet_network.find_lanelet_by_id(lanelets_of_pathSegment[0]) - dist = dist + findDistanceToNearestPoint(laneletObj.center_vertices, path[i].position) # distance to center line + dist = dist + findDistanceToNearestPoint(laneletObj.center_vertices, + path[i].position) # distance to center line end_lanelet_id = lanelets_of_pathSegment - return dist, end_lanelet_id, start_lanelet_id + return dist, end_lanelet_id, start_lanelet_id def reached_goal(self, path: List[State]) -> bool: """ @@ -363,7 +407,6 @@ class MotionPlanner: return True return False - def remove_states_behind_goal(self, path: List[State]) -> List[State]: """ Remove all states that are behind the state which statisfies the goal conditions and return the pruned path. @@ -372,12 +415,12 @@ class MotionPlanner: """ for i in range(len(path)): if self.planningProblem.goal.is_reached(path[i]): - for j in range(i+1, len(path)): + for j in range(i + 1, len(path)): path.pop() return path return path - def check_collision(self, path: List[State]) -> bool: + def check_collision_free(self, path: List[State]) -> bool: """ Checks if path collides with an obstacle. Returns true for no collision and false otherwise. @@ -391,34 +434,37 @@ class MotionPlanner: # create a collision object using the trajectory prediction of the ego vehicle co = create_collision_object(traj_pred) - #check collision for motion primitive - if (self.collisionChecker.collide(co)): + # check collision for motion primitive + if self.collisionChecker.collide(co): return False return True - def translate_primitive_to_current_state(self, primitive: MotionPrimitive, currentPath: List[State]) -> List[State]: + @staticmethod + def translate_primitive_to_current_state(primitive: MotionPrimitive, path_current: List[State]) -> List[State]: """ Uses the value of the given primitive, translate them towards the last state of current path and returns the list of new path. In the newly appended part of the path, the position, orientation and time step are changed, but the velocity is not changed. Attention: The input primitive itself will not be changed after this operation. - :param prmmitive: the primitive to be translated. - :param currentPath: the path whose last state is the reference state for the translation. + :param primitive: the primitive to be translated. + :param path_current: the path whose last state is the reference state for the translation. """ - return primitive.appendTrajectoryToState(currentPath[-1]) + return primitive.appendTrajectoryToState(path_current[-1]) - def append_path(self, currentPath: List[State], pathNew: List[State]) -> List[State]: + @staticmethod + def append_path(path_current: List[State], pathNew: List[State]) -> List[State]: """ Appends a new path to the current path and returns the whole path. - :param currentPath: current path which is to be extended. + :param path_current: current path which is to be extended. :param pathNew: new path which is going to be added to the current path. """ - path = currentPath[:] + path = path_current[:] path.extend(pathNew) return path - def get_successor_primitives(self, cur_primitive: MotionPrimitive) -> List[MotionPrimitive]: + @staticmethod + def get_successor_primitives(cur_primitive: MotionPrimitive) -> List[MotionPrimitive]: """ Returns all possible successor primitives of the current primitive @@ -426,33 +472,72 @@ class MotionPlanner: """ return cur_primitive.Successors - # Define your own heuristic cost function here. def calc_heuristic_cost(self, path: List[State], curPos: State): """ Returns heuristic cost for the path. You should define your own cost function here. - :param path: The path that you want to calculate - :param curPos: Current position/state of your path. Every state has the following variables: position, velocity, orientation, time_step + :param path: The path for which you want to calculate the cost + :param curPos: Last state of your current path. Every state has the following variables: position, velocity, orientation, time_step """ - cost = 0 - distStart = self.calc_heuristic_distance(path[0]) - dist = self.calc_heuristic_distance(path[-1]) - if dist is None: - return None - if distStart < dist: + # *** below is just a sample code from a random previous student, + # *** you are free to come up with your own ideas on how to compute the heuristic cost + # sample code 1 + + # dist_pos = self.calc_heuristic_distance(path[-1]) + # if hasattr(self.planningProblem.goal.state_list[0], 'velocity'): + # v_mean_goal = (self.planningProblem.goal.state_list[0].velocity.start + + # self.planningProblem.goal.state_list[0].velocity.end) / 2 + # dist_vel = abs(path[-1].velocity - v_mean_goal) + # else: + # dist_vel = 0 + + # if hasattr(self.planningProblem.goal.state_list[0], 'orientation'): + # o_mean_goal = (self.planningProblem.goal.state_list[0].orientation.start + + # self.planningProblem.goal.state_list[0].orientation.end) / 2 + # dist_o = abs(path[-1].orientation - o_mean_goal) + # else: + # dist_o = 0 + + # weighs = np.zeros(3) + # weighs[0] = 1.0 + # weighs[1] = 0.3 + # weighs[2] = 0.1 + + # if dist_pos < 5: + # weighs[1] = 1.0 + # weighs[2] = 1.0 + + # return (dist_pos * weighs[0] + \ + # dist_vel * weighs[1] + \ + # dist_o * weighs[2] ) + + # *** below is just a sample code from a random previous student, + # *** you are free to come up with your own ideas on how to compute the heuristic cost + # sample code 2 + + distStartState = self.calc_heuristic_distance(path[0]) + distLastState = self.calc_heuristic_distance(path[-1]) + if distLastState is None: return None + + if distStartState < distLastState: + return None + cost_lanelet, final_lanelet_id, start_lanelet_id = self.calc_heuristic_lanelet(path) if cost_lanelet is None or final_lanelet_id[0] is None: + return None self.calc_path_efficiency(path) self.num_obstacles_in_lanelet_at_time_step(path[-1].time_step, final_lanelet_id[0]) self.is_goal_in_lane(final_lanelet_id[0]) if self.lanelet_cost[final_lanelet_id[0]] == -1: + return None factor = 1 if self.lanelet_cost[final_lanelet_id[0]] > self.lanelet_cost[start_lanelet_id[0]]: + return None if self.lanelet_cost[final_lanelet_id[0]] < self.lanelet_cost[start_lanelet_id[0]]: factor = factor * 0.1 @@ -461,85 +546,171 @@ class MotionPlanner: orientationToGoalDiff = orientation_diff(angleToGoal, path[-1].orientation) if final_lanelet_id[0] in self.goalLanelet_ids: - factor = factor * 0.07 + factor = factor * 0.07 pathLength = calc_travelled_distance(path) cost_time = self.calc_time_cost(path) - weigths = np.zeros(5) - if dist < 0.5: - factor = factor * 0.00001 - elif math.pi - abs(abs(laneletOrientationAtPosition - path[-1].orientation) - math.pi) > math.pi/20: - return None + weigths = np.zeros(6) + if distLastState < 0.5: + factor = factor * 0.00001 + # elif math.pi - abs(abs(laneletOrientationAtPosition - path[-1].orientation) + + if hasattr(self.planningProblem.goal.state_list[0], 'velocity'): + v_mean_goal = (self.planningProblem.goal.state_list[0].velocity.start + + self.planningProblem.goal.state_list[0].velocity.end) / 2 + dist_vel = abs(path[-1].velocity -v_mean_goal) + else: + dist_vel = 0 + weigths[0] = 8.7 weigths[1] = 0.01 weigths[2] = 0.5 weigths[3] = 0.1 weigths[4] = 0.05 - cost = weigths[0] * (cost_lanelet/len(path)) + weigths[1] * abs(orientationToGoalDiff) + weigths[3] * cost_time + weigths[2] * dist + weigths[4] * (100 - pathLength) - if cost < 0: - cost = 0 - return cost*factor + weigths[5] = 1 + cost = weigths[0] * (cost_lanelet / len(path)) + \ + weigths[1] * abs(orientationToGoalDiff) + \ + weigths[3] * cost_time + \ + weigths[2] * distLastState + \ + weigths[4] * (100 - pathLength) + \ + weigths[5] * dist_vel - # Implement your search algorithm here. - def search_alg(self, startSuccessor: List[MotionPrimitive], maxTreeDepth: int, status): + if cost < 0: cost = 0 + return cost * factor + + def search_alg(self, list_successors_start_state: List[MotionPrimitive], max_tree_depth: int, dict_status = None): # -> Tuple(List[State], List[MotionPrimitive]): return None """ Returns the path and the used primitives - :param startSuccessor: All possible primitives for the start state - :param maxTreeDepth: Maximum number of concatenated primitives - :param status: Used for the visualization in the jupyter notebook - """ + :param list_successors_start_state: All connectable primitives (successors) of the start state + :param max_tree_depth: Maximum number of concatenated primitives + :param dict_status: Used for the visualization in the jupyter notebook + """ + + # Here the greedy best first search algorithm is demonstrated. # + + # Every state has the following attributes: .position, .velocity, .orientation, .time_step + # For more information please refer to the commonroad-io tutorial + + # initial values to be fed into the priority queue + # the queue is a heap that always pops up the item with the lowest cost + + total_cost = 0 + path = [self.initial_state] + tree_depth = 0 + path_appended = [self.initial_state] + list_primitives = [] + priority = 0 + + # if the goal state is reached by the current path + if self.reached_goal(path): + # return a pruned path and its corresponding primitives + return self.remove_states_behind_goal(path), list_primitives + + # inputs for PriorityQueue: (total_cost, : total cost of the path so far + # path, : current path + # list_successors_primitive_last, : list of successors of the last primitive in the path + # tree_depth, : tree depth + # path_appended, : the path that is appened in this iteration + # list_primitives), : list of primitives of the current path + # priority : cost of the path / value to be sorted in the heap + list_primitives_copied = copy.copy(list_primitives) + # add initial state into priority queue + self.priority_queue.put((total_cost, # : initial cost is 0 + path, # : initial path only contains the initial state + list_successors_start_state, # : the successors of the initial state + tree_depth, # : initial depth is 0 + path_appended, # : only initial state is added to the path + list_primitives_copied), # : no primitives added to the list yet + priority) # : initial priority is 0 + + + # while the queue is not empty + while not self.priority_queue.empty(): + # get the item with lowest cost from the queue + (total_cost, path, list_successors_primitive_last, tree_depth, _, list_primitives) = self.priority_queue.get() + list_primitives_copied = copy.copy(list_primitives) + + status = {'cost_current': total_cost, + 'tree_depth' : tree_depth, + 'path_current': path} + + if dict_status is not None: dict_status.value = status + + # check whether the tree depth exceeds the maximum allowed number + if tree_depth > max_tree_depth: + print("reached max tree depth") + return None + else: + tree_depth += 1 - ##print("Implement your own search algorithm") + # skip if the time step of the last state of path exceeds that of the goal state + if path[-1].time_step > self.desired_time.end: + continue + + # otherwise, expand all successors of the primitive + for i in range(len(list_successors_primitive_last)): - # inputs for PQ: (state, cost, state_list, successors), priority - ##print("initial: ", self.initial_state) - treeDepth = 0 - self.frontier.put((0, [self.initial_state], startSuccessor, treeDepth, [self.initial_state], []), 0) + # get a primitive from the list of successors + primitive_next = list_successors_primitive_last[i] - while not self.frontier.empty(): - (total_cost, currentPath, successors, treeDepth, appendedPath, primitives) = self.frontier.get() - stat = {} - stat['cost_so_far'] = total_cost - stat['treeDepth'] = treeDepth - stat['currentPath'] = currentPath + # add new primitves to the current path + # we attach the primitive to current path by translating the pritimive, and + # obtain a path containing the translated states + # Note: all motion primitives start at position [0, 0]^T + path_primitive_translated = self.translate_primitive_to_current_state(primitive_next, path) - status.value = stat + # skip if the path is None + if path_primitive_translated is None: + continue - if (treeDepth > maxTreeDepth): - ##print("reached max tree deth") - return (currentPath, primitives) - treeDepth += 1 + # skip if the time step of the last state of path exceeds that of goal state + if path_primitive_translated[0].time_step > self.desired_time.end: + continue - if currentPath[-1].time_step > self.desired_time.end: - continue + # skip this translated path if it is not collision free + if not self.check_collision_free(path_primitive_translated): + continue - if self.reached_goal(currentPath): - ##print("found goal") - return (self.remove_states_behind_goal(currentPath), primitives) + # otherwise, calculated the cost associated with this path + # lower cost implies higher priority when expanding + # in Greedy BFS, the final cost (f) = heuristic cost (h) + cost_final = self.calc_heuristic_cost(path_primitive_translated, path[-1]) - # check all successors of last primitive - for i in range(len(successors)): - nextPrimitive = successors[i] - pathNew = self.translate_primitive_to_current_state(nextPrimitive, currentPath) - if pathNew[0].time_step > self.desired_time.end: + # skip if the cost is not valid + if cost_final is None: continue - cost = self.calc_heuristic_cost(pathNew, currentPath[-1]) - if cost is None: # no primitive found - continue + # if the new primitive passes all conditions listed above, add it into current path - if not self.check_collision(pathNew): - continue + # update total cost + total_cost = total_cost + cost_final + + # add primitive into the list of primitives + list_primitives_copied.append(primitive_next) + + # if the goal state is reached by the new path_primitive_translated + if self.reached_goal(path_primitive_translated): + # concacenate its predecessor and return result + path_new = path + path_primitive_translated - total_cost = total_cost + cost + # return a pruned path and its corresponding primitives + return self.remove_states_behind_goal(path_new), list_primitives_copied - primitivesNew = primitives[:] - primitivesNew.append(nextPrimitive) + # get new path by concatenating current path and the path translated from the primitve + path_new = path + path_primitive_translated - path = self.append_path(currentPath, pathNew) - # push new path with corresponding values into the priority queue - self.frontier.put((total_cost, path, self.get_successor_primitives(nextPrimitive), treeDepth, pathNew, primitivesNew), cost) - return + # push the new path with corresponding values into the priority queue + + self.priority_queue.put( + (total_cost, + path_new, + self.get_successor_primitives(primitive_next), + tree_depth, + path_primitive_translated, + list_primitives_copied), + cost_final) + # return None is no feasible path is found + return None class PriorityQueue: @@ -557,6 +728,7 @@ class PriorityQueue: """ Put an item into the queue and count the number of elements in the queue. The number is saved in self.count. + :param item: item to be put into the queue :param priority: the priority used to sort the queue. It's often the value of some cost function. """ heapq.heappush(self.elements, (np.round(priority * 10000000), self.count, item)) @@ -570,11 +742,12 @@ class PriorityQueue: return None return heapq.heappop(self.elements)[2] + def findClosestVertex(centerVertices: np.ndarray, pos: np.ndarray) -> int: """ Return the index of the closest center vertice to the given position. - :param center_vertices: The vertices of the center line of the Lanelet described as a polyline [[x0,x1,...,xn],[y0,y1,...,yn]] + :param centerVertices: The vertices of the center line of the Lanelet described as a polyline [[x0,x1,...,xn],[y0,y1,...,yn]] :param pos: The position, to which the closest vertex is calculated. """ @@ -584,6 +757,7 @@ def findClosestVertex(centerVertices: np.ndarray, pos: np.ndarray) -> int: distances.append(distance(vertex, pos, 0)) return distances.index(min(distances)) + def calcAngleOfPosition(centerVertices: np.ndarray, pos: np.ndarray) -> float: """ Returns the angle (in world coordinate, radian) of the line defined by 2 nearest lanelet center vertices to the given position. @@ -592,20 +766,23 @@ def calcAngleOfPosition(centerVertices: np.ndarray, pos: np.ndarray) -> float: :param pos: The position to be considered. """ index_closestVert = findClosestVertex(centerVertices, pos) - if index_closestVert + 1 >= centerVertices.size/2.0: + if index_closestVert + 1 >= centerVertices.size / 2.0: index_closestVert = index_closestVert - 1 - return math.atan2(centerVertices[index_closestVert+1][1] - centerVertices[index_closestVert][1], centerVertices[index_closestVert+1][0] - centerVertices[index_closestVert][0]) + return math.atan2(centerVertices[index_closestVert + 1][1] - centerVertices[index_closestVert][1], + centerVertices[index_closestVert + 1][0] - centerVertices[index_closestVert][0]) + def distToClosestPointOnLine(vertexA: np.ndarray, vertexB: np.ndarray, pos: np.ndarray): """ Returns the distance of the given position to a line segment (e.g. the nearest lanelet center line segment to the given position). + :param pos: :param vertexA: The first point of the line segment. :param vertexB: The second point of the line segment. """ - magAB2 = (vertexB[0] - vertexA[0])**2 + (vertexB[1] - vertexA[1])**2 - ABdotAP = (pos[0] - vertexA[0])*(vertexB[0] - vertexA[0]) + (pos[1] - vertexA[1])*(vertexB[1] - vertexA[1]) + magAB2 = (vertexB[0] - vertexA[0]) ** 2 + (vertexB[1] - vertexA[1]) ** 2 + ABdotAP = (pos[0] - vertexA[0]) * (vertexB[0] - vertexA[0]) + (pos[1] - vertexA[1]) * (vertexB[1] - vertexA[1]) s = ABdotAP / magAB2 if s < 0: return distance(vertexA, pos, 0) @@ -613,10 +790,11 @@ def distToClosestPointOnLine(vertexA: np.ndarray, vertexB: np.ndarray, pos: np.n return distance(vertexB, pos, 0) else: newVertex = np.empty(2) - newVertex[0] = vertexA[0] + (vertexB[0] - vertexA[0])*s - newVertex[1] = vertexA[1] + (vertexB[1] - vertexA[1])*s + newVertex[0] = vertexA[0] + (vertexB[0] - vertexA[0]) * s + newVertex[1] = vertexA[1] + (vertexB[1] - vertexA[1]) * s return distance(newVertex, pos, 0) + def findDistanceToNearestPoint(centerVertices: np.ndarray, pos: np.ndarray): """ Returns the closest euclidean distance to a polyline (e.g. defined by lanelet center vertices) according to the given position. @@ -628,19 +806,20 @@ def findDistanceToNearestPoint(centerVertices: np.ndarray, pos: np.ndarray): for vertex in centerVertices: distances.append(distance(vertex, pos, 0)) index_closestVert = distances.index(min(distances)) - dist1 = 0 - dist2 = 0 + if (index_closestVert + 1) < len(centerVertices): - dist1 = distToClosestPointOnLine(centerVertices[index_closestVert], centerVertices[index_closestVert+1], pos) + dist1 = distToClosestPointOnLine(centerVertices[index_closestVert], centerVertices[index_closestVert + 1], pos) else: dist1 = distance(centerVertices[index_closestVert], pos, 0) + if index_closestVert > 0: - dist2 = distToClosestPointOnLine(centerVertices[index_closestVert-1], centerVertices[index_closestVert], pos) + dist2 = distToClosestPointOnLine(centerVertices[index_closestVert - 1], centerVertices[index_closestVert], pos) else: dist2 = distance(centerVertices[index_closestVert], pos, 0) return min(dist1, dist2) + def calc_travelled_distance(path: List[State]): """ Returns the travelled distance of the given path. @@ -649,10 +828,11 @@ def calc_travelled_distance(path: List[State]): """ dist = 0 - for i in range(len(path)-1): - dist = dist + distance(path[i].position, path[i+1].position) + for i in range(len(path) - 1): + dist = dist + distance(path[i].position, path[i + 1].position) return dist + def euclideanDistance(pos1: np.ndarray, pos2: np.ndarray): """ Returns the euclidean distance between 2 points. @@ -662,6 +842,7 @@ def euclideanDistance(pos1: np.ndarray, pos2: np.ndarray): """ return np.sqrt((pos1[0] - pos2[0]) * (pos1[0] - pos2[0]) + (pos1[1] - pos2[1]) * (pos1[1] - pos2[1])) + def manhattanDistance(pos1: np.ndarray, pos2: np.ndarray): """ Returns the manhattan distance between 2 points. @@ -671,6 +852,7 @@ def manhattanDistance(pos1: np.ndarray, pos2: np.ndarray): """ return abs(pos1[0] - pos2[0]) + abs(pos1[1] - pos2[1]) + def chebyshevDistance(pos1: np.ndarray, pos2: np.ndarray): """ Returns the chebyshev distance between 2 points. @@ -680,6 +862,7 @@ def chebyshevDistance(pos1: np.ndarray, pos2: np.ndarray): """ return max(abs(pos1[0] - pos2[0]), abs(pos1[1] - pos2[1])) + def sumOfSquaredDifference(pos1: np.ndarray, pos2: np.ndarray): """ Returns the squared euclidean distance between 2 points. @@ -687,7 +870,8 @@ def sumOfSquaredDifference(pos1: np.ndarray, pos2: np.ndarray): :param pos1: the first point :param pos2: the second point """ - return (pos1[0] - pos2[0])**2 + (pos1[1] - pos2[1])**2 + return (pos1[0] - pos2[0]) ** 2 + (pos1[1] - pos2[1]) ** 2 + def meanAbsoluteError(pos1: np.ndarray, pos2: np.ndarray): """ @@ -696,7 +880,8 @@ def meanAbsoluteError(pos1: np.ndarray, pos2: np.ndarray): :param pos1: the first point :param pos2: the second point """ - return 0.5*(abs(pos1[0] - pos2[0]) + abs(pos1[1] - pos2[1])) + return 0.5 * (abs(pos1[0] - pos2[0]) + abs(pos1[1] - pos2[1])) + def meanSquaredError(pos1: np.ndarray, pos2: np.ndarray): """ @@ -705,7 +890,8 @@ def meanSquaredError(pos1: np.ndarray, pos2: np.ndarray): :param pos1: the first point :param pos2: the second point """ - return 0.5*((pos1[0] - pos2[0])**2 + (pos1[1] - pos2[1])**2) + return 0.5 * ((pos1[0] - pos2[0]) ** 2 + (pos1[1] - pos2[1]) ** 2) + def canberraDistance(pos1: np.ndarray, pos2: np.ndarray): """ @@ -714,7 +900,9 @@ def canberraDistance(pos1: np.ndarray, pos2: np.ndarray): :param pos1: the first point :param pos2: the second point """ - return abs(pos1[0] - pos2[0])/(abs(pos1[0]) + abs(pos2[0])) + abs(pos1[1] - pos2[1])/(abs(pos1[1]) + abs(pos2[1])) + return abs(pos1[0] - pos2[0]) / (abs(pos1[0]) + abs(pos2[0])) + abs(pos1[1] - pos2[1]) / ( + abs(pos1[1]) + abs(pos2[1])) + def cosineDistance(pos1: np.ndarray, pos2: np.ndarray): """ @@ -723,38 +911,44 @@ def cosineDistance(pos1: np.ndarray, pos2: np.ndarray): :param pos1: the first point :param pos2: the second point """ - return 1 - (pos1[0] * pos2[0] + pos1[1] * pos2[1])/(np.sqrt(pos1[0]**2 + pos2[0]**2) * np.sqrt(pos1[1]**2 + pos2[1]**2)) + return 1 - (pos1[0] * pos2[0] + pos1[1] * pos2[1]) / ( + np.sqrt(pos1[0] ** 2 + pos2[0] ** 2) * np.sqrt(pos1[1] ** 2 + pos2[1] ** 2)) -def distance(pos1: np.ndarray, pos2: np.ndarray, type=0): + +def distance(pos1: np.ndarray, pos2: np.ndarray, distance_type=0): """ Returns the distance between 2 points, the type is specified by 'type'. - type: 0 means euclideanDistance, - 1 means manhattanDistance, - 2 means chebyshevDistance, - 3 means sumOfSquaredDifference, - 4 means meanAbsoluteError, - 5 means meanSquaredError, - 6 means canberraDistance, - 7 means cosineDistance. - """ - if (type == 0): + + :param pos1: the first point + :param pos2: the second point + :param distance_type: specifies which kind of distance is used: + 1: manhattanDistance, + 2: chebyshevDistance, + 3: sumOfSquaredDifference, + 4: meanAbsoluteError, + 5: meanSquaredError, + 6: canberraDistance, + 7: cosineDistance. + """ + if distance_type == 0: return euclideanDistance(pos1, pos2) - elif (type == 1): + elif distance_type == 1: return manhattanDistance(pos1, pos2) - elif (type == 2): + elif distance_type == 2: return chebyshevDistance(pos1, pos2) - elif (type == 3): + elif distance_type == 3: return sumOfSquaredDifference(pos1, pos2) - elif (type == 4): + elif distance_type == 4: return meanAbsoluteError(pos1, pos2) - elif (type == 5): + elif distance_type == 5: return meanSquaredError(pos1, pos2) - elif (type == 6): + elif distance_type == 6: return canberraDistance(pos1, pos2) - elif (type == 7): + elif distance_type == 7: return cosineDistance(pos1, pos2) return + def curvature_of_polyline(polyline: np.ndarray): """ Returns the curvature of the given polyline. @@ -765,12 +959,13 @@ def curvature_of_polyline(polyline: np.ndarray): dy_dt = np.gradient(polyline[:, 1]) d2x_dt2 = np.gradient(dx_dt) d2y_dt2 = np.gradient(dy_dt) - curvatureArray = np.abs(d2x_dt2 * dy_dt - dx_dt * d2y_dt2) / (dx_dt * dx_dt + dy_dt * dy_dt)**1.5 + curvatureArray = np.abs(d2x_dt2 * dy_dt - dx_dt * d2y_dt2) / (dx_dt * dx_dt + dy_dt * dy_dt) ** 1.5 curvature = 0 for elem in curvatureArray: curvature = curvature + abs(elem) return curvature + def orientation_diff(orientation_1: float, orientation_2: float) -> float: """ Returns the orientation difference between 2 orientations in radians. @@ -780,6 +975,7 @@ def orientation_diff(orientation_1: float, orientation_2: float) -> float: """ return math.pi - abs(abs(orientation_1 - orientation_2) - math.pi) + def length_of_polyline(polyline: np.ndarray): """ Returns the length of the polyline. @@ -788,6 +984,6 @@ def length_of_polyline(polyline: np.ndarray): """ dist = 0 - for i in range(0, len(polyline)-1): - dist = dist + distance(polyline[i], polyline[i+1]) + for i in range(0, len(polyline) - 1): + dist = dist + distance(polyline[i], polyline[i + 1]) return dist diff --git a/GSMP/motion_automata/automata/MotionPrimitive.py b/GSMP/motion_automata/automata/MotionPrimitive.py new file mode 100644 index 0000000000000000000000000000000000000000..cd5e38e6409ac3b880b92aeb73f5213e7ef2de50 --- /dev/null +++ b/GSMP/motion_automata/automata/MotionPrimitive.py @@ -0,0 +1,166 @@ +import os +import numpy as np +import xml.etree.ElementTree as et +from typing import List +from copy import deepcopy +from automata.States import StartState, FinalState +from commonroad.scenario.trajectory import Trajectory +from commonroad.scenario.trajectory import State + +from commonroad.common.solution_writer import CommonRoadSolutionWriter, VehicleType, CostFunction +from commonroad.common.solution_writer import VehicleModel as VM +from solution_checker import * + +class MotionPrimitive: + def __init__(self, startState: StartState, finalState: FinalState, timeStepSize, trajectory: Trajectory): + """ + Initialisation of a motion primitive. + + :param startState: start state of the primitive + :param finalState: final state of the primitive + :param trajectory: trajectory of the primitive + """ + self.startState = startState + self.finalState = finalState + self.timeStepSize = timeStepSize + self.trajectory = trajectory + self.vehicle_type = VehicleType.BMW_320i + self.vehicle_model = VM.KS + # a list to store connectable successive primitives from current primitive + self.Successors = [] + self.veh_type_id = 1 # default + + def __str__(self): + return "Primitive: \n\t {}\t=>\n\t{}".format(str(self.startState), str(self.finalState)) + + def print_info(self): + kwarg = {'position' : np.array([self.startState.x, self.startState.y]), + 'velocity' : self.startState.velocity, + 'steering_angle': self.startState.steering_angle, + 'orientation' : self.startState.orientation, + 'time_step' : self.startState.time_step} + state_start = State(**kwarg) + + # add final state into the trajectory + kwarg = {'position' : np.array([self.finalState.x, self.finalState.y]), + 'velocity' : self.finalState.velocity, + 'steering_angle': self.finalState.steering_angle, + 'orientation' : self.finalState.orientation, + 'time_step' : self.finalState.time_step} + state_final = State(**kwarg) + + print(state_start) + + for state in self.trajectory.state_list: + print(state) + + print(state_final) + + def mirror(self) -> None: + """ + Mirrors the current primitive so that it describes a primitive in the opposite direction. + """ + self.finalState.y = - self.finalState.y + self.finalState.orientation = - self.finalState.orientation + for i in range(len(self.trajectory.state_list)): + state = self.trajectory.state_list[i] + self.trajectory.state_list[i].position[1] = - self.trajectory.state_list[i].position[1] + state.orientation = - state.orientation + self.trajectory.state_list[i] = state + + def checkConnectivityToNext(self, other: 'MotionPrimitive') -> bool: + """ + Any primitive whose first state's velocity is in the velocity range of the last state of the current primitive is considered as connected. + Returns true if the two primitives are connected. + + :param other: the next motion primitive to be checked + """ + # if (self.finalState.velocity - self.finalState.vRange >= other.startState.velocity - other.startState.vRange and + # self.finalState.velocity + self.finalState.vRange <= other.startState.velocity + other.startState.vRange): + # return True + + if abs(self.finalState.velocity - other.startState.velocity) < 0.01 and \ + abs(self.finalState.steering_angle - other.startState.steering_angle) < 0.01 : + return True + + return False + + def appendTrajectoryToState(self, state: State) -> List[State]: + """ + Appends the primitive to the given state and returns the new list of states including the intermediate steps. + + :param state: the state to which the trajectory will be appended + """ + + # deep copy to prevent manipulation of original data + trajectory = deepcopy(self.trajectory) + + # rotate the trajectory by the orientation of the given state + trajectory.translate_rotate(np.zeros(2), state.orientation) + # translate the trajectory by the position of the given state + trajectory.translate_rotate(state.position, 0) + + # trajectory includes all states of the primitive + # as its first state is the same as the last state of the primitive to be connected + # we pop out the first state + trajectory.state_list.pop(0) + + # we modify the time steps of the trajectory + time_step_state = int(state.time_step) + for i in range(len(trajectory.state_list)): + trajectory.state_list[i].time_step = time_step_state + i + 1 + + # check connectability between the first state of the trajectory and the state + state_start = deepcopy(state) + state_end = deepcopy(trajectory.state_list[0]) + + state_start.time_step = 0 + state_end.time_step = 1 + + trajectory_to_be_cheked = Trajectory(0, [state_start, state_end]) + + if self.check_validity(trajectory_to_be_cheked): + return trajectory.state_list + else: + return None + + def check_validity(self, trajectory_to_be_cheked): + """ + Checks feasibility of the trajectory + """ + + if self.veh_type_id == 1: + veh_type = VehicleType.FORD_ESCORT + elif self.veh_type_id == 2: + veh_type = VehicleType.BMW_320i + elif self.veh_type_id == 3: + veh_type = VehicleType.VW_VANAGON + + csw = CommonRoadSolutionWriter(output_dir=os.getcwd(), + scenario_id=0, + step_size=0.1, + vehicle_type=veh_type, + vehicle_model=self.vehicle_model, + cost_function=CostFunction.JB1) + + # use solution writer to generate target xml tree + csw.add_solution_trajectory(trajectory=trajectory_to_be_cheked, planning_problem_id=100) + xmlTree = csw.root_node + # generate states to be checked + [node] = xmlTree.findall('ksTrajectory') + + veh_trajectory = KSTrajectory.from_xml(node) + veh_model = KinematicSingleTrackModel(self.veh_type_id, veh_trajectory, None) + + # validate + result = TrajectoryValidator.is_trajectory_valid(veh_trajectory, veh_model, 0.1) + + return result + + def costs(self) -> float: + """ + Returns euclidean distance between the last state of current primitive and [0,0]. + """ + pos1 = [0,0] + pos2 = [self.finalState.x, self.finalState.y] + return np.sqrt((pos1[0] - pos2[0]) * (pos1[0] - pos2[0]) + (pos1[1] - pos2[1]) * (pos1[1] - pos2[1])) diff --git a/GSMP/motion_automata/automata/MotionPrimitiveParser.py b/GSMP/motion_automata/automata/MotionPrimitiveParser.py new file mode 100644 index 0000000000000000000000000000000000000000..db607be3811ce8ca7b93fd8f0060d91ac972d858 --- /dev/null +++ b/GSMP/motion_automata/automata/MotionPrimitiveParser.py @@ -0,0 +1,147 @@ +import numpy as np +from commonroad.scenario.trajectory import Trajectory, State +from automata.MotionPrimitive import MotionPrimitive +from automata.States import StartState, FinalState + + +class MotionPrimitiveParser: + """ + Parse and create trajectories from given XML node + """ + @classmethod + def createFromNode(cls, xmlNode) -> MotionPrimitive: + """ + Create a motion primitive from given XML node. + + :param cls: + :param xmlNode: cls and xmlNode are often given together as an element of the list returned by xmlTree.findall(...) + + """ + # read from xml node and create start state + startNode = xmlNode.find('Start') + startX = float(startNode.find('x').text) + startY = float(startNode.find('y').text) + startSteeringAngle = float(startNode.find('steering_angle').text) + startVelocity = float(startNode.find('velocity').text) + startOrientation = float(startNode.find('orientation').text) + startTimeStep = float(startNode.find('time_step').text) + + startState = StartState(startX, startY, startSteeringAngle, startVelocity, startOrientation, startTimeStep) + + # read from xml node and create final state + finalNode = xmlNode.find('Final') + finalX = float(finalNode.find('x').text) + finalY = float(finalNode.find('y').text) + finalSteeringAngle = float(finalNode.find('steering_angle').text) + finalVelocity = float(finalNode.find('velocity').text) + finalOrientation = float(finalNode.find('orientation').text) + finalTimeStep = float(finalNode.find('time_step').text) + + finalState = FinalState(finalX, finalY, finalSteeringAngle, finalVelocity, finalOrientation, finalTimeStep) + + # create trajectory from path node and start/final states + pathNode = xmlNode.find('Path') + timeStepSize = 1.0 / (len(pathNode) + 1) + + trajectory = MotionPrimitiveParser.createTrajectoryFromPathStates(pathNode, startState, finalState, timeStepSize) + + # create and return motion primitive + return MotionPrimitive(startState, finalState, timeStepSize, trajectory) + + @classmethod + def createTrajectoryFromPathStates(cls, xmlNode, startState: StartState, finalState: FinalState, timeStepSize: float): + """ + Creates trajectory state list from the path values described in the xml file. + + :param cls: + :param xmlNode: cls and xmlNode are often given together as the return value of xmlNode.find(...) + :param startState: start State of the trajectory + :param finalState: final State of the trajectory + :param timeStepSize: time step size + """ + vertices = [] + steering_angles = [] + velocities = [] + orientations = [] + time_steps = [] + + # insert start state + vertices.append([startState.x, startState.y]) + steering_angles.append(startState.steering_angle) + velocities.append(startState.velocity) + orientations.append(startState.orientation) + time_steps.append(int(startState.time_step)) + + # insert trajectory states + skipCounter = 0 + if xmlNode is not None: + list_states = xmlNode.findall('State') + for state in list_states: + + # # todo: down-sampling of trajectory list_states + # if skipCounter < (1 / timeStepSize) * (20 / np.max([startState.velocity, finalState.velocity])): + # # (len(states) / (timeStepSize * 10)):# * 20 / ((startState.velocity + finalState.velocity) / 2): + # skipCounter = skipCounter + 1 + # continue + # skipCounter = 0 + + x = float(state.find('x').text) + y = float(state.find('y').text) + steering_angle = float(state.find('steering_angle').text) + velocity = float(state.find('velocity').text) + orientation = float(state.find('orientation').text) + time_step = int(state.find('time_step').text) + + vertices.append([x, y]) + steering_angles.append(steering_angle) + velocities.append(velocity) + orientations.append(orientation) + time_steps.append(time_step) + + # insert final state + vertices.append([finalState.x, finalState.y]) + steering_angles.append(finalState.steering_angle) + velocities.append(finalState.velocity) + orientations.append(finalState.orientation) + time_steps.append(int(finalState.time_step)) + + trajectory = MotionPrimitiveParser.create_from_vertices(np.array(vertices), + np.array(steering_angles), + np.array(velocities), + np.array(orientations), + np.array(time_steps)) + + return trajectory + + @classmethod + def create_from_vertices(cls, vertices: np.ndarray, steering_angles: np.ndarray, velocities: np.ndarray, + orientations: np.ndarray, time_steps: np.ndarray) -> Trajectory: + """ + Creates a trajectory from a set of given positions, orientations, velocities and a starting time step. + + :param vertices: a set of positions for every state of the trajectory + :param t0: starting time step of the trajectory + :param orientation: a set of orientations for every state of the trajectory + :param velocity: a set of velocities for every state of the trajectory + """ + + assert len(vertices) == len(steering_angles) == len(velocities) == len(orientations) == len(time_steps), "The sizes of state elements should be equal!" + + list_states = [] + + for i in range(len(vertices)): + kwarg = {'position': np.array([vertices[i][0], vertices[i][1]]), + 'velocity': velocities[i], + 'steering_angle': steering_angles[i], + 'orientation': orientations[i], + 'time_step': time_steps[i]} + + # append state + list_states.append(State(**kwarg)) + + + # create trajectory + trajectory = Trajectory(initial_time_step=int(time_steps[0]), state_list=list_states) + + return trajectory + diff --git a/GSMP/motion_automata/automata/States.py b/GSMP/motion_automata/automata/States.py new file mode 100644 index 0000000000000000000000000000000000000000..1d0928bed974a02cc8a984f0d62d3e4e4bbca3ee --- /dev/null +++ b/GSMP/motion_automata/automata/States.py @@ -0,0 +1,61 @@ +class StartState: + """ + class to store start state of a motion primitive + """ + def __init__(self, x, y, steering_angle, velocity, orientation, time_step = 0): + """ + Initialisation of class StartState. + + :param x: the position in x axis + :param y: the position in y axis + :param steering_angle: the steering angle of vehicle + :param velocity: the velocity of the state + :param orientation: the orientation of the final state + """ + self.x = x + self.y = y + self.steering_angle = steering_angle + self.velocity = velocity + self.orientation = orientation + self.time_step = time_step + + def __str__(self) -> str: + """ + Returns the velocity information of StartState. + """ + return "pos: ({}, {})m, vel: {} m/s, ori: {} rad, steer: {} rad".format(round(self.x, 2), + round(self.y, 2), + round(self.velocity, 2), + round(self.orientation, 2), + round(self.steering_angle, 2)) + +class FinalState: + """ + class to store final state of a motion primitive + """ + def __init__(self, x, y, steering_angle, velocity, orientation, time_step = 0): + """ + Initialisation of class StartState. + + :param x: the position in x axis + :param y: the position in y axis + :param steering_angle: the steering angle of vehicle + :param velocity: the velocity of the state + :param orientation: the orientation of the final state + """ + self.x = x + self.y = y + self.steering_angle = steering_angle + self.velocity = velocity + self.orientation = orientation + self.time_step = time_step + + def __str__(self) -> str: + """ + Returns the velocity, orientation and position information of the final state. + """ + return "pos: ({}, {})m, vel: {} m/s, ori: {} rad, steer: {} rad".format(round(self.x, 2), + round(self.y, 2), + round(self.velocity, 2), + round(self.orientation, 2), + round(self.steering_angle, 2)) \ No newline at end of file diff --git a/GSMP/motion_automata/motion_primitives/V_0.0_20.0_Vstep_1.0_SA_-0.91_0.91_SAstep_0.23_T_0.5_Model_FORD_ESCORT.xml b/GSMP/motion_automata/motion_primitives/V_0.0_20.0_Vstep_1.0_SA_-0.91_0.91_SAstep_0.23_T_0.5_Model_FORD_ESCORT.xml new file mode 100644 index 0000000000000000000000000000000000000000..72ff12b76929f8bc485f1dbdd6d53ab52260fcd5 --- /dev/null +++ b/GSMP/motion_automata/motion_primitives/V_0.0_20.0_Vstep_1.0_SA_-0.91_0.91_SAstep_0.23_T_0.5_Model_FORD_ESCORT.xml @@ -0,0 +1,173419 @@ + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.11374999999999999 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.022750000000000003 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.045500000000000006 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.06825 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.091 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.22500000000000003 + 0.0 + 0.0 + 0.9999999999999999 + 0.0 + 5 + + + + 0.005000000000000001 + 0.0 + 0.0 + 0.2 + 0.0 + 1 + + + 0.030000000000000006 + 0.0 + 0.0 + 0.4 + 0.0 + 2 + + + 0.07500000000000001 + 0.0 + 0.0 + 0.6 + 0.0 + 3 + + + 0.14 + 0.0 + 0.0 + 0.7999999999999999 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.2249991315071958 + 0.0004934807352438413 + 0.11374999999999999 + 0.9999999999999999 + 0.006790340533720683 + 5 + + + + 0.005000000000000001 + 0.0 + 0.022750000000000003 + 0.2 + 2.3771441712876474e-05 + 1 + + + 0.029999999891199888 + 2.0207571292814496e-06 + 0.045500000000000006 + 0.4 + 0.00033288634412041186 + 2 + + + 0.07499999241997263 + 2.6515374418513012e-05 + 0.06825 + 0.6 + 0.001308377687202691 + 3 + + + 0.13999988468215221 + 0.00014155716929334293 + 0.091 + 0.7999999999999999 + 0.0033326620728502633 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.45000000000000007 + 0.0 + 0.0 + 1.9999999999999998 + 0.0 + 5 + + + + 0.010000000000000002 + 0.0 + 0.0 + 0.4 + 0.0 + 1 + + + 0.06000000000000001 + 0.0 + 0.0 + 0.8 + 0.0 + 2 + + + 0.15000000000000002 + 0.0 + 0.0 + 1.2 + 0.0 + 3 + + + 0.28 + 0.0 + 0.0 + 1.5999999999999999 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.4499930520884322 + 0.001973908795391933 + 0.11374999999999999 + 1.9999999999999998 + 0.013580681067441366 + 5 + + + + 0.010000000000000002 + 0.0 + 0.022750000000000003 + 0.4 + 4.754288342575295e-05 + 1 + + + 0.059999999129599066 + 8.083028466468493e-06 + 0.045500000000000006 + 0.8 + 0.0006657726882408237 + 2 + + + 0.14999993935978775 + 0.00010606147798821516 + 0.06825 + 1.2 + 0.002616755374405382 + 3 + + + 0.279999077458082 + 0.0005662278123175486 + 0.091 + 1.5999999999999999 + 0.0066653241457005265 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.6750000000000002 + 0.0 + 0.0 + 3.0 + 0.0 + 5 + + + + 0.015000000000000003 + 0.0 + 0.0 + 0.6000000000000001 + 0.0 + 1 + + + 0.09000000000000002 + 0.0 + 0.0 + 1.2000000000000002 + 0.0 + 2 + + + 0.22500000000000003 + 0.0 + 0.0 + 1.8000000000000003 + 0.0 + 3 + + + 0.4200000000000001 + 0.0 + 0.0 + 2.4000000000000004 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.6749765509720775 + 0.00444124174411401 + 0.11374999999999999 + 3.0 + 0.020371021601162054 + 5 + + + + 0.015000000000000003 + 0.0 + 0.022750000000000003 + 0.6000000000000001 + 7.131432513862941e-05 + 1 + + + 0.08999999706239686 + 1.8186813859589217e-05 + 0.045500000000000006 + 1.2000000000000002 + 0.0009986590323612355 + 2 + + + 0.2249997953393215 + 0.00023863825165160987 + 0.06825 + 1.8000000000000003 + 0.003925133061608073 + 3 + + + 0.41999688642588806 + 0.0012740093345105065 + 0.091 + 2.4000000000000004 + 0.00999798621855079 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.9000000000000001 + 0.0 + 0.0 + 3.9999999999999996 + 0.0 + 5 + + + + 0.020000000000000004 + 0.0 + 0.0 + 0.8 + 0.0 + 1 + + + 0.12000000000000002 + 0.0 + 0.0 + 1.6 + 0.0 + 2 + + + 0.30000000000000004 + 0.0 + 0.0 + 2.4 + 0.0 + 3 + + + 0.56 + 0.0 + 0.0 + 3.1999999999999997 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 0.89994441769515 + 0.007895408855593061 + 0.11374999999999999 + 3.9999999999999996 + 0.02716136213488273 + 5 + + + + 0.020000000000000004 + 0.0 + 0.022750000000000003 + 0.8 + 9.50857668515059e-05 + 1 + + + 0.1199999930367926 + 3.23321130553571e-05 + 0.045500000000000006 + 1.6 + 0.0013315453764816475 + 2 + + + 0.29999951487851717 + 0.00042424559697958313 + 0.06825 + 2.4 + 0.005233510748810764 + 3 + + + 0.559992619692311 + 0.002264897411619893 + 0.091 + 3.1999999999999997 + 0.013330648291401053 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 1.1250000000000002 + 0.0 + 0.0 + 5.0 + 0.0 + 5 + + + + 0.025 + 0.0 + 0.0 + 1.0 + 0.0 + 1 + + + 0.15000000000000002 + 0.0 + 0.0 + 2.0 + 0.0 + 2 + + + 0.375 + 0.0 + 0.0 + 3.0 + 0.0 + 3 + + + 0.7000000000000001 + 0.0 + 0.0 + 4.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 0.0 + 0.0 + 0 + + + 1.1248914422576335 + 0.012336311116625441 + 0.11374999999999999 + 5.0 + 0.033951702668603416 + 5 + + + + 0.025 + 0.0 + 0.022750000000000003 + 1.0 + 0.00011885720856438233 + 1 + + + 0.14999998639998563 + 5.0518925699171e-05 + 0.045500000000000006 + 2.0 + 0.001664431720602059 + 2 + + + 0.37499905249741916 + 0.0006628833761714742 + 0.06825 + 3.0 + 0.006541888436013454 + 3 + + + 0.6999855853770549 + 0.003538885989729968 + 0.091 + 4.0 + 0.016663310364251314 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 3.469446951953614e-18 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.09100000000000001 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.06825000000000002 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.04550000000000001 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.022750000000000006 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.22749999999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.1365 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.15925 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.182 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.20475 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.22499920064674572 + 0.0005421623448089469 + 3.469446951953614e-18 + 0.9999999999999999 + 0.0039271719660436905 + 5 + + + + 0.005000000000000001 + 0.0 + 0.09100000000000001 + 0.2 + 0.00021468428209638177 + 1 + + + 0.029999997104858844 + 1.1087806213986595e-05 + 0.06825000000000002 + 0.4 + 0.0010963006445577623 + 2 + + + 0.07499995032173963 + 7.470574751964988e-05 + 0.04550000000000001 + 0.6 + 0.0022625800907520883 + 3 + + + 0.13999973303375757 + 0.0002417542030292925 + 0.022750000000000006 + 0.7999999999999999 + 0.0033328366997795408 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.22499671629001472 + 0.0010384882539351892 + 0.11375 + 0.9999999999999999 + 0.010743062466919293 + 5 + + + + 0.005000000000000001 + 0.0 + 0.11375 + 0.2 + 0.00023873472148709543 + 1 + + + 0.029999995867915796 + 1.31304087406733e-05 + 0.11375 + 0.4 + 0.0014324083289225726 + 2 + + + 0.07499990410718288 + 0.00010146218920043437 + 0.11375 + 0.6 + 0.003581020822306431 + 3 + + + 0.1399992718994003 + 0.000384361869496134 + 0.11375 + 0.7999999999999999 + 0.006684572201638671 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.2249923975492915 + 0.0015420373247116439 + 0.22749999999999998 + 0.9999999999999999 + 0.017686358847577126 + 5 + + + + 0.005000000000000001 + 0.0 + 0.1365 + 0.2 + 0.0002628477527748248 + 1 + + + 0.02999999440144906 + 1.5182088915343094e-05 + 0.15925 + 0.4 + 0.001770770643585954 + 2 + + + 0.0749998418886968 + 0.00012842941122704276 + 0.182 + 0.6 + 0.004913567889337068 + 3 + + + 0.139998567230732 + 0.0005285708325292322 + 0.20475 + 0.7999999999999999 + 0.010085535605953764 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.4499936051907224 + 0.002168639231261263 + 3.469446951953614e-18 + 1.9999999999999998 + 0.007854343932087381 + 5 + + + + 0.010000000000000002 + 0.0 + 0.09100000000000001 + 0.4 + 0.00042936856419276354 + 1 + + + 0.059999976838872614 + 4.435121830473706e-05 + 0.06825000000000002 + 0.8 + 0.0021926012891155247 + 2 + + + 0.1499996025741411 + 0.00029882269891974756 + 0.04550000000000001 + 1.2 + 0.0045251601815041766 + 3 + + + 0.27999786427332674 + 0.0009670142336006995 + 0.022750000000000006 + 1.5999999999999999 + 0.0066656733995590816 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.4499737306734424 + 0.004153859602446457 + 0.11375 + 1.9999999999999998 + 0.021486124933838585 + 5 + + + + 0.010000000000000002 + 0.0 + 0.11375 + 0.4 + 0.00047746944297419086 + 1 + + + 0.05999996694333032 + 5.252162366929088e-05 + 0.11375 + 0.8 + 0.002864816657845145 + 2 + + + 0.14999923285836328 + 0.00040584794762358814 + 0.11375 + 1.2 + 0.007162041644612862 + 3 + + + 0.2799941752231472 + 0.0015374350928596936 + 0.11375 + 1.5999999999999999 + 0.013369144403277342 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.44993918244348075 + 0.006167807760669086 + 0.22749999999999998 + 1.9999999999999998 + 0.03537271769515425 + 5 + + + + 0.010000000000000002 + 0.0 + 0.1365 + 0.4 + 0.0005256955055496496 + 1 + + + 0.059999955211599856 + 6.07283377127204e-05 + 0.15925 + 0.8 + 0.003541541287171908 + 2 + + + 0.14999873511212697 + 0.0005137158960858157 + 0.182 + 1.2 + 0.009827135778674136 + 3 + + + 0.27998853796105855 + 0.0021142481066188444 + 0.20475 + 1.5999999999999999 + 0.02017107121190753 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.6749784176129441 + 0.0048794002156036 + 3.469446951953614e-18 + 3.0 + 0.01178151589813107 + 5 + + + + 0.015000000000000003 + 0.0 + 0.09100000000000001 + 0.6000000000000001 + 0.0006440528462891453 + 1 + + + 0.08999992183120582 + 9.979021661862686e-05 + 0.06825000000000002 + 1.2000000000000002 + 0.003288901933673288 + 2 + + + 0.22499865868898716 + 0.0006723499807248033 + 0.04550000000000001 + 1.8000000000000003 + 0.006787740272256266 + 3 + + + 0.4199927919408511 + 0.00217577235619039 + 0.022750000000000006 + 2.4000000000000004 + 0.009998510099338623 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.6749113430102842 + 0.009345833813974344 + 0.11375 + 3.0 + 0.032229187400757885 + 5 + + + + 0.015000000000000003 + 0.0 + 0.11375 + 0.6000000000000001 + 0.0007162041644612863 + 1 + + + 0.08999988843376217 + 0.00011817361090565432 + 0.11375 + 1.2000000000000002 + 0.0042972249867677175 + 2 + + + 0.22499741090203995 + 0.0009131548477411998 + 0.11375 + 1.8000000000000003 + 0.010743062466919294 + 3 + + + 0.4199803415353087 + 0.0034591825151078907 + 0.11375 + 2.4000000000000004 + 0.020053716604916016 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.6747947522727178 + 0.013876286770026076 + 0.22749999999999998 + 3.0 + 0.053059076542731384 + 5 + + + + 0.015000000000000003 + 0.0 + 0.1365 + 0.6000000000000001 + 0.0007885432583244744 + 1 + + + 0.08999984883919117 + 0.00013663869254619448 + 0.15925 + 1.2000000000000002 + 0.0053123119307578615 + 2 + + + 0.22499573101778728 + 0.001155854208132251 + 0.182 + 1.8000000000000003 + 0.014740703668011204 + 3 + + + 0.41996131626657845 + 0.004756926154116867 + 0.20475 + 2.4000000000000004 + 0.030256606817861298 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.899948842061989 + 0.008674394558814452 + 3.469446951953614e-18 + 3.9999999999999996 + 0.015708687864174762 + 5 + + + + 0.020000000000000004 + 0.0 + 0.09100000000000001 + 0.8 + 0.0008587371283855271 + 1 + + + 0.11999981471104212 + 0.0001774047683996264 + 0.06825000000000002 + 1.6 + 0.004385202578231049 + 2 + + + 0.29999682060030225 + 0.001195286137145886 + 0.04550000000000001 + 2.4 + 0.009050320363008353 + 3 + + + 0.5599829142911374 + 0.003868015678343905 + 0.022750000000000006 + 3.1999999999999997 + 0.013331346799118163 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.8997898566935628 + 0.016613943863663806 + 0.11375 + 3.9999999999999996 + 0.04297224986767717 + 5 + + + + 0.020000000000000004 + 0.0 + 0.11375 + 0.8 + 0.0009549388859483817 + 1 + + + 0.11999973554676979 + 0.00021008631398279452 + 0.11375 + 1.6 + 0.00572963331569029 + 2 + + + 0.2999938628957144 + 0.0016233788436934554 + 0.11375 + 2.4 + 0.014324083289225725 + 3 + + + 0.5599534026793925 + 0.006149542212575191 + 0.11375 + 3.1999999999999997 + 0.026738288806554683 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 0.8995135251153686 + 0.024665767045309213 + 0.22749999999999998 + 3.9999999999999996 + 0.0707454353903085 + 5 + + + + 0.020000000000000004 + 0.0 + 0.1365 + 0.8 + 0.0010513910110992993 + 1 + + + 0.11999964169303583 + 0.00024291306367259797 + 0.15925 + 1.6 + 0.007083082574343816 + 2 + + + 0.2999898809787009 + 0.0020548356033695653 + 0.182 + 2.4 + 0.019654271557348273 + 3 + + + 0.5599083073748606 + 0.00845642886924413 + 0.20475 + 3.1999999999999997 + 0.04034214242381506 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 1.1249000829377802 + 0.013553551227455274 + 3.469446951953614e-18 + 5.0 + 0.019635859830218455 + 5 + + + + 0.025 + 0.0 + 0.09100000000000001 + 1.0 + 0.0010734214104819086 + 1 + + + 0.14999963810759387 + 0.00027719482778931797 + 0.06825000000000002 + 2.0 + 0.005481503222788812 + 2 + + + 0.3749937902454734 + 0.0018676291300859542 + 0.04550000000000001 + 3.0 + 0.011312900453760441 + 3 + + + 0.6999666296279881 + 0.006043726150804063 + 0.022750000000000006 + 4.0 + 0.016664183498897707 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 1.1245895804154409 + 0.02595753597497781 + 0.11375 + 5.0 + 0.05371531233459646 + 5 + + + + 0.025 + 0.0 + 0.11375 + 1.0 + 0.001193673607435477 + 1 + + + 0.14999948348997122 + 0.0003282596538470144 + 0.11375 + 2.0 + 0.007162041644612862 + 2 + + + 0.37498801351039157 + 0.0025365142713199194 + 0.11375 + 3.0 + 0.017905104111532157 + 3 + + + 0.6999089909180539 + 0.009608427494871959 + 0.11375 + 4.0 + 0.033422861008193354 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 0.0 + 0.0 + 0 + + + 1.124049949776405 + 0.03853385889276405 + 0.22749999999999998 + 5.0 + 0.08843179423788561 + 5 + + + + 0.025 + 0.0 + 0.1365 + 1.0 + 0.001314238763874124 + 1 + + + 0.14999930018205776 + 0.00037955132545162615 + 0.15925 + 2.0 + 0.008853853217929768 + 2 + + + 0.37498023640618033 + 0.003210647840363252 + 0.182 + 3.0 + 0.024567839446685336 + 3 + + + 0.6998209182413355 + 0.013212509720304931 + 0.20475 + 4.0 + 0.050427678029768816 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.11375000000000005 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.20475000000000002 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.18200000000000002 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.15925000000000003 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.13650000000000004 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.3412500000000002 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.25025000000000003 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.2730000000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.2957500000000001 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.31850000000000017 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.22499261227663717 + 0.0015920075989533156 + 0.11375000000000005 + 0.9999999999999999 + 0.014747597803575985 + 5 + + + + 0.005000000000000001 + 0.0 + 0.20475000000000002 + 0.2 + 0.0004588038349317338 + 1 + + + 0.029999985746480256 + 2.4488547601536856e-05 + 0.18200000000000002 + 0.4 + 0.002554332510670442 + 2 + + + 0.07499971112713438 + 0.00017789140657651568 + 0.15925000000000003 + 0.6 + 0.0058929477400068864 + 3 + + + 0.13999809619936004 + 0.0006314109570088026 + 0.13650000000000004 + 0.7999999999999999 + 0.010085728937484249 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.22498651565818123 + 0.002104393635343394 + 0.2275 + 0.9999999999999999 + 0.021770259460062967 + 5 + + + + 0.005000000000000001 + 0.0 + 0.2275 + 0.2 + 0.00048378354355695487 + 1 + + + 0.029999983031630317 + 2.6608087064040137e-05 + 0.2275 + 0.4 + 0.0029027012613417292 + 2 + + + 0.07499960621736769 + 0.00020560744487392314 + 0.2275 + 0.6 + 0.007256753153354323 + 3 + + + 0.13999701007537999 + 0.0007788829164537795 + 0.2275 + 0.7999999999999999 + 0.013545939219594735 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.2249782697163616 + 0.002632003579037118 + 0.3412500000000002 + 0.9999999999999999 + 0.02906152010589295 + 5 + + + + 0.005000000000000001 + 0.0 + 0.25025000000000003 + 0.2 + 0.0005088951684747332 + 1 + + + 0.029999980048722584 + 2.8746758452594023e-05 + 0.2730000000000001 + 0.4 + 0.003255821951100353 + 2 + + + 0.07499948257575491 + 0.00023376773399483755 + 0.2957500000000001 + 0.6 + 0.008650291458998255 + 3 + + + 0.13999563871485937 + 0.0009297299137454422 + 0.31850000000000017 + 0.7999999999999999 + 0.017109920029333172 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.4499408998655571 + 0.006367726435655278 + 0.11375000000000005 + 1.9999999999999998 + 0.02949519560715197 + 5 + + + + 0.010000000000000002 + 0.0 + 0.20475000000000002 + 0.4 + 0.0009176076698634676 + 1 + + + 0.05999988597188893 + 9.79541184193952e-05 + 0.18200000000000002 + 0.8 + 0.005108665021340884 + 2 + + + 0.1499976890249872 + 0.0007115614601130224 + 0.15925000000000003 + 1.2 + 0.011785895480013773 + 3 + + + 0.2799847697757588 + 0.0025255927830725683 + 0.13650000000000004 + 1.5999999999999999 + 0.020171457874968497 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.449892131223463 + 0.008416797229745311 + 0.2275 + 1.9999999999999998 + 0.043540518920125934 + 5 + + + + 0.010000000000000002 + 0.0 + 0.2275 + 0.4 + 0.0009675670871139097 + 1 + + + 0.05999986425310962 + 0.00010643225427709069 + 0.2275 + 0.8 + 0.0058054025226834585 + 2 + + + 0.14999684975412278 + 0.000822423045870488 + 0.2275 + 1.2 + 0.014513506306708645 + 3 + + + 0.2799760810742711 + 0.003115428603524991 + 0.2275 + 1.5999999999999999 + 0.02709187843918947 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.4498261739845931 + 0.010526386972758463 + 0.3412500000000002 + 1.9999999999999998 + 0.0581230402117859 + 5 + + + + 0.010000000000000002 + 0.0 + 0.25025000000000003 + 0.4 + 0.0010177903369494663 + 1 + + + 0.059999840389874146 + 0.00011498691347598711 + 0.2730000000000001 + 0.8 + 0.006511643902200706 + 2 + + + 0.1499958606328998 + 0.0009350606721910072 + 0.2957500000000001 + 1.2 + 0.01730058291799651 + 3 + + + 0.27996511076014435 + 0.0037187348068782483 + 0.31850000000000017 + 1.5999999999999999 + 0.034219840058666344 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.6748005463410205 + 0.014326244685419792 + 0.11375000000000005 + 3.0 + 0.04424279341072796 + 5 + + + + 0.015000000000000003 + 0.0 + 0.20475000000000002 + 0.6000000000000001 + 0.0013764115047952014 + 1 + + + 0.08999961515538904 + 0.00022039649649350392 + 0.18200000000000002 + 1.2000000000000002 + 0.007662997532011327 + 2 + + + 0.22499220050383817 + 0.0016009976621232259 + 0.15925000000000003 + 1.8000000000000003 + 0.01767884322002066 + 3 + + + 0.4199485990106133 + 0.005682392347280382 + 0.13650000000000004 + 2.4000000000000004 + 0.03025718681245275 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.6746359763906927 + 0.01893487913273484 + 0.2275 + 3.0 + 0.06531077838018891 + 5 + + + + 0.015000000000000003 + 0.0 + 0.2275 + 0.6000000000000001 + 0.0014513506306708646 + 1 + + + 0.08999954185462236 + 0.00023947221970223266 + 0.2275 + 1.2000000000000002 + 0.008708103784025187 + 2 + + + 0.2249893680055588 + 0.0018504266023254886 + 0.2275 + 1.8000000000000003 + 0.021770259460062967 + 3 + + + 0.41991927627627557 + 0.007009327887729653 + 0.2275 + 2.4000000000000004 + 0.04063781765878421 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.6744134286142974 + 0.02367826916310338 + 0.3412500000000002 + 3.0 + 0.08718456031767888 + 5 + + + + 0.015000000000000003 + 0.0 + 0.25025000000000003 + 0.6000000000000001 + 0.0015266855054241997 + 1 + + + 0.08999946131635109 + 0.0002587201040674525 + 0.2730000000000001 + 1.2000000000000002 + 0.009767465853301061 + 2 + + + 0.22498602978712626 + 0.0021038480236575223 + 0.2957500000000001 + 1.8000000000000003 + 0.02595087437699477 + 3 + + + 0.41988225467241014 + 0.008366460171546545 + 0.31850000000000017 + 2.4000000000000004 + 0.051329760087999526 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.8995272517997445 + 0.02546604282638618 + 0.11375000000000005 + 3.9999999999999996 + 0.05899039121430394 + 5 + + + + 0.020000000000000004 + 0.0 + 0.20475000000000002 + 0.8 + 0.0018352153397269352 + 1 + + + 0.11999908777661267 + 0.0003918153218910296 + 0.18200000000000002 + 1.6 + 0.010217330042681768 + 2 + + + 0.29998151245308824 + 0.002846179182106055 + 0.15925000000000003 + 2.4 + 0.023571790960027546 + 3 + + + 0.559878163994027 + 0.01010155444470378 + 0.13650000000000004 + 3.1999999999999997 + 0.040342915749936994 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.8991372404193894 + 0.03365475420813744 + 0.2275 + 3.9999999999999996 + 0.08708103784025187 + 5 + + + + 0.020000000000000004 + 0.0 + 0.2275 + 0.8 + 0.0019351341742278195 + 1 + + + 0.11999891402702412 + 0.0004257275134455697 + 0.2275 + 1.6 + 0.011610805045366917 + 2 + + + 0.2999747985187793 + 0.003289584447169934 + 0.2275 + 2.4 + 0.02902701261341729 + 3 + + + 0.5598086636728754 + 0.012460065524547412 + 0.2275 + 3.1999999999999997 + 0.05418375687837894 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 0.8986099118802956 + 0.04207951849304731 + 0.3412500000000002 + 3.9999999999999996 + 0.1162460804235718 + 5 + + + + 0.020000000000000004 + 0.0 + 0.25025000000000003 + 0.8 + 0.0020355806738989327 + 1 + + + 0.11999872312198472 + 0.0004599457285572463 + 0.2730000000000001 + 1.6 + 0.013023287804401412 + 2 + + + 0.29996688592272347 + 0.003740078471622857 + 0.2957500000000001 + 2.4 + 0.03460116583599302 + 3 + + + 0.5597209193994559 + 0.014871981949519133 + 0.31850000000000017 + 3.1999999999999997 + 0.06843968011733269 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 1.124076741118383 + 0.03978499391840837 + 0.11375000000000005 + 5.0 + 0.07373798901787992 + 5 + + + + 0.025 + 0.0 + 0.20475000000000002 + 1.0 + 0.0022940191746586686 + 1 + + + 0.14999821831589571 + 0.0006122100907073045 + 0.18200000000000002 + 2.0 + 0.012771662553352207 + 2 + + + 0.3749638918808187 + 0.0044470768580097885 + 0.15925000000000003 + 3.0 + 0.029464738700034424 + 3 + + + 0.69976204752896 + 0.01578272181628031 + 0.13650000000000004 + 4.0 + 0.05042864468742123 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 1.12331520188903 + 0.0525709852556316 + 0.2275 + 5.0 + 0.10885129730031484 + 5 + + + + 0.025 + 0.0 + 0.2275 + 1.0 + 0.002418917717784774 + 1 + + + 0.14999787896217687 + 0.0006651974776576806 + 0.2275 + 2.0 + 0.014513506306708644 + 2 + + + 0.3749507790685968 + 0.00513984944798705 + 0.2275 + 3.0 + 0.03628376576677161 + 3 + + + 0.6996263183226167 + 0.019466920265345043 + 0.2275 + 4.0 + 0.06772969609797368 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 0.0 + 0.0 + 0 + + + 1.1222857456296518 + 0.0657187577240424 + 0.3412500000000002 + 5.0 + 0.1453076005294648 + 5 + + + + 0.025 + 0.0 + 0.25025000000000003 + 1.0 + 0.0025444758423736656 + 1 + + + 0.14999750610200857 + 0.0007186629446108079 + 0.2730000000000001 + 2.0 + 0.016279109755501762 + 2 + + + 0.37493532532686324 + 0.005843680175645073 + 0.2957500000000001 + 3.0 + 0.043251457294991275 + 3 + + + 0.6994549695034105 + 0.023234006714443853 + 0.31850000000000017 + 4.0 + 0.08554960014666586 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.2274999999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.31849999999999995 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.2957499999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.27299999999999985 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.2502499999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.45500000000000024 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.36400000000000005 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.3867500000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.40950000000000014 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.4322500000000002 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.2249786536458134 + 0.002684691405080015 + 0.2274999999999998 + 0.9999999999999999 + 0.025963382158511766 + 5 + + + + 0.005000000000000001 + 0.0 + 0.31849999999999995 + 0.2 + 0.0007154847453447714 + 1 + + + 0.02999996456846867 + 3.85579852152613e-05 + 0.2957499999999999 + 0.4 + 0.004081861017493096 + 2 + + + 0.07499924871300666 + 0.0002859106640599263 + 0.27299999999999985 + 0.6 + 0.009682752137479536 + 3 + + + 0.13999479630800982 + 0.0010381422672537338 + 0.2502499999999998 + 0.7999999999999999 + 0.01711015517061349 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.224968268085817 + 0.003228104290685081 + 0.34125 + 0.9999999999999999 + 0.03339660149197085 + 5 + + + + 0.005000000000000001 + 0.0 + 0.34125 + 0.2 + 0.0007421466998215744 + 1 + + + 0.029999960068340496 + 4.081804021756877e-05 + 0.34125 + 0.4 + 0.004452880198929447 + 2 + + + 0.0749990733132524 + 0.0003154103216785677 + 0.34125 + 0.6 + 0.011132200497323616 + 3 + + + 0.1399929638722131 + 0.0011948251811564853 + 0.34125 + 0.7999999999999999 + 0.020780107595004083 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.22495512305936505 + 0.003796481238495877 + 0.45500000000000024 + 0.9999999999999999 + 0.04127047855522642 + 5 + + + + 0.005000000000000001 + 0.0 + 0.36400000000000005 + 0.2 + 0.0007690249533257982 + 1 + + + 0.029999955225580258 + 4.310946589226265e-05 + 0.3867500000000001 + 0.4 + 0.004831691474562668 + 2 + + + 0.07499887389978395 + 0.00034563845693916673 + 0.40950000000000014 + 0.6 + 0.012630409515196717 + 3 + + + 0.13999076543123667 + 0.0013570426445573599 + 0.4322500000000002 + 0.7999999999999999 + 0.024620267075835138 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.4498292433804716 + 0.010737252268855496 + 0.2274999999999998 + 1.9999999999999998 + 0.05192676431702353 + 5 + + + + 0.010000000000000002 + 0.0 + 0.31849999999999995 + 0.4 + 0.0014309694906895429 + 1 + + + 0.05999971654804011 + 0.00015423165826043383 + 0.2957499999999999 + 0.8 + 0.008163722034986193 + 2 + + + 0.14999398975816253 + 0.0011436250904147817 + 0.27299999999999985 + 1.2 + 0.01936550427495907 + 3 + + + 0.27995837184229994 + 0.0041523362884077555 + 0.2502499999999998 + 1.5999999999999999 + 0.03422031034122698 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.44974617768021274 + 0.012909611242448086 + 0.34125 + 1.9999999999999998 + 0.0667932029839417 + 5 + + + + 0.010000000000000002 + 0.0 + 0.34125 + 0.4 + 0.001484293399643149 + 1 + + + 0.05999968054709555 + 0.0001632718215991903 + 0.34125 + 0.8 + 0.008905760397858894 + 2 + + + 0.14999258659009324 + 0.0012616169780065249 + 0.34125 + 1.2 + 0.022264400994647233 + 3 + + + 0.27994371358733944 + 0.004778928673114394 + 0.34125 + 1.5999999999999999 + 0.041560215190008166 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.44964105296562185 + 0.015181123012080813 + 0.45500000000000024 + 1.9999999999999998 + 0.08254095711045284 + 5 + + + + 0.010000000000000002 + 0.0 + 0.36400000000000005 + 0.4 + 0.0015380499066515963 + 1 + + + 0.05999964180511188 + 0.00017243745950226515 + 0.3867500000000001 + 0.8 + 0.009663382949125335 + 2 + + + 0.14999099132466379 + 0.0013825209800859177 + 0.40950000000000014 + 1.2 + 0.025260819030393435 + 3 + + + 0.2799261280732178 + 0.0054276036847954266 + 0.4322500000000002 + 1.5999999999999999 + 0.049240534151670276 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.6744237763543648 + 0.024153143367003554 + 0.2274999999999998 + 3.0 + 0.0778901464755353 + 5 + + + + 0.015000000000000003 + 0.0 + 0.31849999999999995 + 0.6000000000000001 + 0.002146454236034314 + 1 + + + 0.08999904335127093 + 0.00034702017133549876 + 0.2957499999999999 + 1.2000000000000002 + 0.012245583052479287 + 2 + + + 0.2249797157381596 + 0.002573090582619419 + 0.27299999999999985 + 1.8000000000000003 + 0.029048256412438606 + 3 + + + 0.4198595127199396 + 0.009341883772299976 + 0.2502499999999998 + 2.4000000000000004 + 0.05133046551184047 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.6741435352299293 + 0.029036105510380064 + 0.34125 + 3.0 + 0.10018980447591255 + 5 + + + + 0.015000000000000003 + 0.0 + 0.34125 + 0.6000000000000001 + 0.0022264400994647235 + 1 + + + 0.0899989218485378 + 0.0003673603263340789 + 0.34125 + 1.2000000000000002 + 0.01335864059678834 + 2 + + + 0.22497498021447515 + 0.0028385470446566454 + 0.34125 + 1.8000000000000003 + 0.03339660149197085 + 3 + + + 0.4198100480356215 + 0.010751194435059487 + 0.34125 + 2.4000000000000004 + 0.06234032278501225 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.6737889389266841 + 0.034139525583474 + 0.45500000000000024 + 3.0 + 0.12381143566567929 + 5 + + + + 0.015000000000000003 + 0.0 + 0.36400000000000005 + 0.6000000000000001 + 0.0023070748599773945 + 1 + + + 0.08999879109489528 + 0.00038798276863296266 + 0.3867500000000001 + 1.2000000000000002 + 0.014495074423688002 + 2 + + + 0.22496959643168418 + 0.0031105490294312246 + 0.40950000000000014 + 1.8000000000000003 + 0.037891228545590155 + 3 + + + 0.41975070825128674 + 0.012209982674751414 + 0.4322500000000002 + 2.4000000000000004 + 0.07386080122750543 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.8986344018023631 + 0.04292480209210802 + 0.2274999999999998 + 3.9999999999999996 + 0.10385352863404707 + 5 + + + + 0.020000000000000004 + 0.0 + 0.31849999999999995 + 0.8 + 0.0028619389813790857 + 1 + + + 0.11999773239362543 + 0.0006169221114464761 + 0.2957499999999999 + 1.6 + 0.016327444069972386 + 2 + + + 0.29995191979675984 + 0.004574219316697275 + 0.27299999999999985 + 2.4 + 0.03873100854991814 + 3 + + + 0.5596670188380951 + 0.016605621069180978 + 0.2502499999999998 + 3.1999999999999997 + 0.06844062068245396 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.8979704769170305 + 0.05159356957080842 + 0.34125 + 3.9999999999999996 + 0.1335864059678834 + 5 + + + + 0.020000000000000004 + 0.0 + 0.34125 + 0.8 + 0.002968586799286298 + 1 + + + 0.11999744438865599 + 0.0006530818580791536 + 0.34125 + 1.6 + 0.017811520795717788 + 2 + + + 0.2999406954110485 + 0.005046078987070133 + 0.34125 + 2.4 + 0.044528801989294466 + 3 + + + 0.5595497921980191 + 0.01910976277800209 + 0.34125 + 3.1999999999999997 + 0.08312043038001633 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 0.8971306144410274 + 0.06064770967768005 + 0.45500000000000024 + 3.9999999999999996 + 0.16508191422090568 + 5 + + + + 0.020000000000000004 + 0.0 + 0.36400000000000005 + 0.8 + 0.0030760998133031927 + 1 + + + 0.11999713445592901 + 0.0006897433729669852 + 0.3867500000000001 + 1.6 + 0.01932676589825067 + 2 + + + 0.2999279346417311 + 0.005529558381637174 + 0.40950000000000014 + 2.4 + 0.05052163806078687 + 3 + + + 0.5594091725105403 + 0.02170134631885695 + 0.4322500000000002 + 3.1999999999999997 + 0.09848106830334055 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 1.1223334819895499 + 0.06704164660177712 + 0.2274999999999998 + 5.0 + 0.12981691079255883 + 5 + + + + 0.025 + 0.0 + 0.31849999999999995 + 1.0 + 0.0035774237267238566 + 1 + + + 0.14999557109492945 + 0.0009639355004145014 + 0.2957499999999999 + 2.0 + 0.020409305087465475 + 2 + + + 0.3749060958892918 + 0.007146888346288197 + 0.27299999999999985 + 3.0 + 0.04841376068739767 + 3 + + + 0.6993497107603783 + 0.025941919423957502 + 0.2502499999999998 + 4.0 + 0.08555077585306745 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 1.121037633174172 + 0.08056239579088659 + 0.34125 + 5.0 + 0.16698300745985425 + 5 + + + + 0.025 + 0.0 + 0.34125 + 1.0 + 0.003710733499107872 + 1 + + + 0.14999500858901313 + 0.0010204340419713816 + 0.34125 + 2.0 + 0.02226440099464723 + 2 + + + 0.37488417466543494 + 0.007884042669436049 + 0.34125 + 3.0 + 0.05566100248661807 + 3 + + + 0.6991208101817195 + 0.02985203093320945 + 0.34125 + 4.0 + 0.10390053797502041 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 0.0 + 0.0 + 0 + + + 1.1193989383648053 + 0.09467214688604363 + 0.45500000000000024 + 5.0 + 0.2063523927761321 + 5 + + + + 0.025 + 0.0 + 0.36400000000000005 + 1.0 + 0.00384512476662899 + 1 + + + 0.14999440325625885 + 0.0010777164440831939 + 0.3867500000000001 + 2.0 + 0.02415845737281333 + 2 + + + 0.3748592532713115 + 0.008639319145051744 + 0.40950000000000014 + 3.0 + 0.06315204757598357 + 3 + + + 0.6988462567021012 + 0.0338977296431616 + 0.4322500000000002 + 4.0 + 0.12310133537917567 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.3412499999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.43224999999999997 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.4094999999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.38674999999999987 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.3639999999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.5687500000000002 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.47775 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.5005000000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.5232500000000001 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.5460000000000002 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.2249557218720159 + 0.003853629682462334 + 0.3412499999999998 + 0.9999999999999999 + 0.03791083590134753 + 5 + + + + 0.005000000000000001 + 0.0 + 0.43224999999999997 + 0.2 + 0.000993063304482698 + 1 + + + 0.029999931067561277 + 5.3748925180288664e-05 + 0.4094999999999999 + 0.4 + 0.005727422993625232 + 2 + + + 0.07499850898420753 + 0.0004021799101792627 + 0.38674999999999987 + 0.6 + 0.013749957433527117 + 3 + + + 0.1399894509976315 + 0.0014745967509951843 + 0.3639999999999998 + 0.7999999999999999 + 0.0246205777930456 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.22493978443183527 + 0.004446660973740963 + 0.455 + 0.9999999999999999 + 0.04600626522801594 + 5 + + + + 0.005000000000000001 + 0.0 + 0.455 + 0.2 + 0.0010223614495114654 + 1 + + + 0.029999924221393092 + 5.622980581196665e-05 + 0.455 + 0.4 + 0.006134168697068792 + 2 + + + 0.0749982414250302 + 0.0004344983202852641 + 0.455 + 0.6 + 0.015335421742671978 + 3 + + + 0.13998664766862007 + 0.0016459208787399345 + 0.455 + 0.7999999999999999 + 0.028626120586321024 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.22492001501476688 + 0.0050775448142301866 + 0.5687500000000002 + 0.9999999999999999 + 0.05477035599792414 + 5 + + + + 0.005000000000000001 + 0.0 + 0.47775 + 0.2 + 0.0010519875259912563 + 1 + + + 0.0299999169017145 + 5.875824913137781e-05 + 0.5005000000000001 + 0.4 + 0.006552729167564591 + 2 + + + 0.0749979405759284 + 0.00046792130350316265 + 0.5232500000000001 + 0.6 + 0.016994832473139664 + 3 + + + 0.13998333642181313 + 0.0018256373823744777 + 0.5460000000000002 + 0.7999999999999999 + 0.03288985152966888 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.44964583687954585 + 0.015409972645318615 + 0.3412499999999998 + 1.9999999999999998 + 0.07582167180269506 + 5 + + + + 0.010000000000000002 + 0.0 + 0.43224999999999997 + 0.4 + 0.001986126608965396 + 1 + + + 0.059999448541592254 + 0.00021499493328397455 + 0.4094999999999999 + 0.8 + 0.011454845987250464 + 2 + + + 0.14998807208779474 + 0.0016086704173925949 + 0.38674999999999987 + 1.2 + 0.027499914867054234 + 3 + + + 0.2799156136920119 + 0.005897712536930291 + 0.3639999999999998 + 1.5999999999999999 + 0.0492411555860912 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.4495183942638224 + 0.017779309513564143 + 0.455 + 1.9999999999999998 + 0.09201253045603187 + 5 + + + + 0.010000000000000002 + 0.0 + 0.455 + 0.4 + 0.002044722899022931 + 1 + + + 0.05999939377248301 + 0.00022491833631553212 + 0.455 + 0.8 + 0.012268337394137584 + 2 + + + 0.1499859317030151 + 0.0017379297332437726 + 0.455 + 1.2 + 0.030670843485343956 + 3 + + + 0.2798931907467243 + 0.00658271093050225 + 0.455 + 1.5999999999999999 + 0.05725224117264205 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.4493603363815243 + 0.020298786618062663 + 0.5687500000000002 + 1.9999999999999998 + 0.10954071199584828 + 5 + + + + 0.010000000000000002 + 0.0 + 0.47775 + 0.4 + 0.0021039750519825126 + 1 + + + 0.05999933521533256 + 0.00023503197548005033 + 0.5005000000000001 + 0.8 + 0.013105458335129182 + 2 + + + 0.1499835250288035 + 0.0018716041033951909 + 0.5232500000000001 + 1.2 + 0.03398966494627933 + 3 + + + 0.2798667063568365 + 0.007301178558167267 + 0.5460000000000002 + 1.5999999999999999 + 0.06577970305933777 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.6738050475993735 + 0.034655395877853476 + 0.3412499999999998 + 3.0 + 0.11373250770404261 + 5 + + + + 0.015000000000000003 + 0.0 + 0.43224999999999997 + 0.6000000000000001 + 0.0029791899134480938 + 1 + + + 0.08999813883407282 + 0.00048373572200911905 + 0.4094999999999999 + 1.2000000000000002 + 0.017182268980875697 + 2 + + + 0.22495974450078815 + 0.0036193238574209674 + 0.38674999999999987 + 1.8000000000000003 + 0.04124987230058136 + 3 + + + 0.4197152283320003 + 0.013267324256914896 + 0.3639999999999998 + 2.4000000000000004 + 0.07386173337913682 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.6733752487353091 + 0.03997595445872237 + 0.455 + 3.0 + 0.13801879568404782 + 5 + + + + 0.015000000000000003 + 0.0 + 0.455 + 0.6000000000000001 + 0.0030670843485343957 + 1 + + + 0.08999795398965806 + 0.0005060629307259399 + 0.455 + 1.2000000000000002 + 0.018402506091206375 + 2 + + + 0.22495252120073234 + 0.0039101036040936395 + 0.455 + 1.8000000000000003 + 0.04600626522801594 + 3 + + + 0.4196395716268445 + 0.01480745296604919 + 0.455 + 2.4000000000000004 + 0.08587836175896309 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.6728423512521621 + 0.045629573073376554 + 0.5687500000000002 + 3.0 + 0.16431106799377243 + 5 + + + + 0.015000000000000003 + 0.0 + 0.47775 + 0.6000000000000001 + 0.0031559625779737695 + 1 + + + 0.0899977563608407 + 0.0005288181159251519 + 0.5005000000000001 + 1.2000000000000002 + 0.019658187502693776 + 2 + + + 0.22494439934237997 + 0.004210805081342193 + 0.5232500000000001 + 1.8000000000000003 + 0.050984497419419 + 3 + + + 0.4195502182181633 + 0.01642251163085784 + 0.5460000000000002 + 2.4000000000000004 + 0.09866955458900667 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.8971686751370658 + 0.061567195165850824 + 0.3412499999999998 + 3.9999999999999996 + 0.1516433436053901 + 5 + + + + 0.020000000000000004 + 0.0 + 0.43224999999999997 + 0.8 + 0.003972253217930792 + 1 + + + 0.11999558836800327 + 0.0008599674542178298 + 0.4094999999999999 + 1.6 + 0.022909691974500927 + 2 + + + 0.29990458355438543 + 0.006433894142413143 + 0.38674999999999987 + 2.4 + 0.05499982973410847 + 3 + + + 0.5593250922581235 + 0.023580061076870846 + 0.3639999999999998 + 3.1999999999999997 + 0.0984823111721824 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.8961509538006848 + 0.07099998380017994 + 0.455 + 3.9999999999999996 + 0.18402506091206375 + 5 + + + + 0.020000000000000004 + 0.0 + 0.455 + 0.8 + 0.004089445798045862 + 1 + + + 0.1199951502226894 + 0.0008996591544427529 + 0.455 + 1.6 + 0.02453667478827517 + 2 + + + 0.29988746331239796 + 0.006950702237897072 + 0.455 + 2.4 + 0.06134168697068791 + 3 + + + 0.5591458266406809 + 0.02631528688344737 + 0.455 + 3.1999999999999997 + 0.1145044823452841 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 0.8948896059666607 + 0.08101306882148195 + 0.5687500000000002 + 3.9999999999999996 + 0.21908142399169656 + 5 + + + + 0.020000000000000004 + 0.0 + 0.47775 + 0.8 + 0.004207950103965025 + 1 + + + 0.11999468177439124 + 0.0009401115653169621 + 0.5005000000000001 + 1.6 + 0.026210916670258363 + 2 + + + 0.29986821371368544 + 0.0074851187518471494 + 0.5232500000000001 + 2.4 + 0.06797932989255866 + 3 + + + 0.558934130163713 + 0.02918278683041277 + 0.5460000000000002 + 3.1999999999999997 + 0.13155940611867553 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 1.119472967507371 + 0.0961136212762529 + 0.3412499999999998 + 5.0 + 0.18955417950673764 + 5 + + + + 0.025 + 0.0 + 0.43224999999999997 + 1.0 + 0.004965316522413489 + 1 + + + 0.1499913835829142 + 0.0013436847579842693 + 0.4094999999999999 + 2.0 + 0.028637114968126157 + 2 + + + 0.37481364979123516 + 0.010052036789654144 + 0.38674999999999987 + 3.0 + 0.06874978716763558 + 3 + + + 0.6986820884170357 + 0.0368312059301847 + 0.3639999999999998 + 4.0 + 0.12310288896522799 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 1.1174878930800678 + 0.11080022450141876 + 0.455 + 5.0 + 0.23003132614007965 + 5 + + + + 0.025 + 0.0 + 0.455 + 1.0 + 0.005111807247557326 + 1 + + + 0.14999052784142228 + 0.0014057007991110856 + 0.455 + 2.0 + 0.030670843485343956 + 2 + + + 0.3747802159728675 + 0.010859280924104226 + 0.455 + 3.0 + 0.07667710871335989 + 3 + + + 0.6983321329613843 + 0.04109941248714431 + 0.455 + 4.0 + 0.14313060293160512 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 0.0 + 0.0 + 0 + + + 1.115028879623173 + 0.12636988309217928 + 0.5687500000000002 + 5.0 + 0.2738517799896207 + 5 + + + + 0.025 + 0.0 + 0.47775 + 1.0 + 0.005259937629956282 + 1 + + + 0.14998961291638496 + 0.0014689051765544897 + 0.5005000000000001 + 2.0 + 0.03276364583782295 + 2 + + + 0.3747426246588005 + 0.011693977529831607 + 0.5232500000000001 + 3.0 + 0.08497416236569832 + 3 + + + 0.6979189248313382 + 0.04557242159695757 + 0.5460000000000002 + 4.0 + 0.16444925764834442 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.45499999999999974 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.5459999999999999 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.5232499999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.5004999999999998 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.4777499999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.6825000000000002 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.5915 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.6142500000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.6370000000000001 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.6597500000000002 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.22492090884519114 + 0.0051414672388404165 + 0.45499999999999974 + 0.9999999999999999 + 0.05101382019145448 + 5 + + + + 0.005000000000000001 + 0.0 + 0.5459999999999999 + 0.2 + 0.0013025116969809872 + 1 + + + 0.029999880811002022 + 7.065476894698275e-05 + 0.5232499999999999 + 0.4 + 0.00755422567108871 + 2 + + + 0.07499739551154709 + 0.0005311377158748378 + 0.5004999999999998 + 0.6 + 0.018246537430573785 + 3 + + + 0.1399813731884883 + 0.0019570635094959933 + 0.4777499999999998 + 0.7999999999999999 + 0.03289029350582904 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.22489721550024017 + 0.005809166814609211 + 0.56875 + 0.9999999999999999 + 0.06010893335141255 + 5 + + + + 0.005000000000000001 + 0.0 + 0.56875 + 0.2 + 0.0013357540744758348 + 1 + + + 0.029999870642838804 + 7.34663092510764e-05 + 0.56875 + 0.4 + 0.008014524446855008 + 2 + + + 0.0749969980547329 + 0.0005676836704868547 + 0.56875 + 0.6 + 0.02003631111713752 + 3 + + + 0.13997720748853876 + 0.002150383284286515 + 0.56875 + 0.7999999999999999 + 0.037401114085323366 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.2248678136475708 + 0.006533086447888802 + 0.6825000000000002 + 0.9999999999999999 + 0.0701982821013749 + 5 + + + + 0.005000000000000001 + 0.0 + 0.5915 + 0.2 + 0.0013694834225781698 + 1 + + + 0.0299998597726674 + 7.634848246185987e-05 + 0.6142500000000001 + 0.4 + 0.008492370442737675 + 2 + + + 0.07499655109841644 + 0.000605870171424929 + 0.6370000000000001 + 0.6 + 0.021935938565443028 + 3 + + + 0.1399722857309973 + 0.0023561687233710892 + 0.6597500000000002 + 0.7999999999999999 + 0.04229564227298804 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.449367469472433 + 0.02055498657515222 + 0.45499999999999974 + 1.9999999999999998 + 0.10202764038290896 + 5 + + + + 0.010000000000000002 + 0.0 + 0.5459999999999999 + 0.4 + 0.0026050233939619743 + 1 + + + 0.05999904649131316 + 0.0002826173302682789 + 0.5232499999999999 + 0.8 + 0.01510845134217742 + 2 + + + 0.14997916474733908 + 0.0021244370923045553 + 0.5004999999999998 + 1.2 + 0.03649307486114757 + 3 + + + 0.27985100338819713 + 0.007826668472218024 + 0.4777499999999998 + 1.5999999999999999 + 0.06578058701165808 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.44917807016338124 + 0.023220312430248073 + 0.56875 + 1.9999999999999998 + 0.1202178667028251 + 5 + + + + 0.010000000000000002 + 0.0 + 0.56875 + 0.4 + 0.0026715081489516695 + 1 + + + 0.05999896514661019 + 0.0002938632588693884 + 0.56875 + 0.8 + 0.016029048893710016 + 2 + + + 0.14997598532013207 + 0.0022705929524859583 + 0.56875 + 1.2 + 0.04007262223427504 + 3 + + + 0.27981768729198553 + 0.00859936411609974 + 0.56875 + 1.5999999999999999 + 0.07480222817064673 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.4489430980079715 + 0.026108179939689433 + 0.6825000000000002 + 1.9999999999999998 + 0.1403965642027498 + 5 + + + + 0.010000000000000002 + 0.0 + 0.5915 + 0.4 + 0.0027389668451563397 + 1 + + + 0.05999887818594013 + 0.00030539169228527995 + 0.6142500000000001 + 0.8 + 0.01698474088547535 + 2 + + + 0.1499724099671624 + 0.002423305045108093 + 0.6370000000000001 + 1.2 + 0.043871877130886056 + 3 + + + 0.279778327188299 + 0.009421737906743034 + 0.6597500000000002 + 1.5999999999999999 + 0.08459128454597609 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.672866326780454 + 0.04620793343777946 + 0.45499999999999974 + 3.0 + 0.15304146057436346 + 5 + + + + 0.015000000000000003 + 0.0 + 0.5459999999999999 + 0.6000000000000001 + 0.003907535090942962 + 1 + + + 0.08999678192672754 + 0.0006358824474427143 + 0.5232499999999999 + 1.2000000000000002 + 0.02266267701326613 + 2 + + + 0.22492968470629277 + 0.004779556838995423 + 0.5004999999999998 + 1.8000000000000003 + 0.05473961229172136 + 3 + + + 0.41949723699686076 + 0.017604059442919984 + 0.4777499999999998 + 2.4000000000000004 + 0.09867088051748714 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.6722279329326295 + 0.05218441797323693 + 0.56875 + 3.0 + 0.1803268000542377 + 5 + + + + 0.015000000000000003 + 0.0 + 0.56875 + 0.6000000000000001 + 0.004007262223427504 + 1 + + + 0.08999650739174558 + 0.0006611849144968113 + 0.56875 + 1.2000000000000002 + 0.024043573340565026 + 2 + + + 0.2249189554179875 + 0.005108302691534496 + 0.56875 + 1.8000000000000003 + 0.06010893335141257 + 3 + + + 0.41938484861492226 + 0.019340437579881742 + 0.56875 + 2.4000000000000004 + 0.11220334225597013 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.6714362656124686 + 0.05865287228497658 + 0.6825000000000002 + 3.0 + 0.2105948463041247 + 5 + + + + 0.015000000000000003 + 0.0 + 0.5915 + 0.6000000000000001 + 0.0041084502677345095 + 1 + + + 0.08999621390342823 + 0.0006871229168411387 + 0.6142500000000001 + 1.2000000000000002 + 0.02547711132821303 + 2 + + + 0.22490689027537827 + 0.005451777748216643 + 0.6370000000000001 + 1.8000000000000003 + 0.06580781569632908 + 3 + + + 0.4192520867459213 + 0.0211879002055627 + 0.6597500000000002 + 2.4000000000000004 + 0.12688692681896413 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.8949461098589954 + 0.08204600872698395 + 0.45499999999999974 + 3.9999999999999996 + 0.20405528076581791 + 5 + + + + 0.020000000000000004 + 0.0 + 0.5459999999999999 + 0.8 + 0.005210046787923949 + 1 + + + 0.11999237203600903 + 0.0011304413930609378 + 0.5232499999999999 + 1.6 + 0.03021690268435484 + 2 + + + 0.29983333893601355 + 0.008495928216422182 + 0.5004999999999998 + 2.4 + 0.07298614972229514 + 3 + + + 0.5588085991155292 + 0.03128131485206586 + 0.4777499999999998 + 3.1999999999999997 + 0.13156117402331616 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.893435627522065 + 0.09261993723169934 + 0.56875 + 3.9999999999999996 + 0.2404357334056502 + 5 + + + + 0.020000000000000004 + 0.0 + 0.56875 + 0.8 + 0.005343016297903339 + 1 + + + 0.11999172129767369 + 0.0011754213856918938 + 0.56875 + 1.6 + 0.03205809778742003 + 2 + + + 0.2998079107913048 + 0.009080104409925231 + 0.56875 + 2.4 + 0.08014524446855008 + 3 + + + 0.5585423743073582 + 0.03436276930623019 + 0.56875 + 3.1999999999999997 + 0.14960445634129346 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 0.8915636018178186 + 0.10404678072421732 + 0.6825000000000002 + 3.9999999999999996 + 0.2807931284054996 + 5 + + + + 0.020000000000000004 + 0.0 + 0.5915 + 0.8 + 0.005477933690312679 + 1 + + + 0.11999102563475048 + 0.0012215309686054226 + 0.6142500000000001 + 1.6 + 0.0339694817709507 + 2 + + + 0.2997793174882206 + 0.009690410322489537 + 0.6370000000000001 + 2.4 + 0.08774375426177211 + 3 + + + 0.5582279398218737 + 0.037639988760132304 + 0.6597500000000002 + 3.1999999999999997 + 0.16918256909195217 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 1.115138418982601 + 0.127993351431636 + 0.45499999999999974 + 5.0 + 0.25506910095727237 + 5 + + + + 0.025 + 0.0 + 0.5459999999999999 + 1.0 + 0.006512558484904935 + 1 + + + 0.14998510178737512 + 0.001766281949014326 + 0.5232499999999999 + 2.0 + 0.037771128355443544 + 2 + + + 0.37467452080550145 + 0.013272755152258533 + 0.5004999999999998 + 3.0 + 0.0912326871528689 + 3 + + + 0.6976738827260012 + 0.04884735326126469 + 0.4777499999999998 + 4.0 + 0.1644514675291452 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 0.0 + 0.0 + 0 + + + 1.1121951478408068 + 0.14441302408350642 + 0.56875 + 5.0 + 0.30054466675706276 + 5 + + + + 0.025 + 0.0 + 0.56875 + 1.0 + 0.006678770372379173 + 1 + + + 0.14998383084231792 + 0.001836558826162988 + 0.56875 + 2.0 + 0.04007262223427504 + 2 + + + 0.37462486711233517 + 0.014185006476275554 + 0.56875 + 3.0 + 0.10018155558568759 + 3 + + + 0.6971543573527713 + 0.05365120619942641 + 0.56875 + 4.0 + 0.18700557042661684 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.5687499999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.65975 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.6369999999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.6142499999999999 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.5914999999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.7962500000000002 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.70525 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.7280000000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.7507500000000001 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.7735000000000002 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.22486914236172606 + 0.006607093083963228 + 0.5687499999999998 + 0.9999999999999999 + 0.06585142275106397 + 5 + + + + 0.005000000000000001 + 0.0 + 0.65975 + 0.2 + 0.0016594089765996788 + 1 + + + 0.029999806054351322 + 9.011476882142234e-05 + 0.6369999999999999 + 0.4 + 0.00965115709660644 + 2 + + + 0.07499574002969278 + 0.0006790128653390958 + 0.6142499999999999 + 0.6 + 0.023384169226073344 + 3 + + + 0.13996936461468867 + 0.0025082215866977587 + 0.5914999999999998 + 0.7999999999999999 + 0.04229631638477879 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.22483381949498016 + 0.007385773696911572 + 0.6825 + 0.9999999999999999 + 0.07643355292773871 + 5 + + + + 0.005000000000000001 + 0.0 + 0.6825 + 0.2 + 0.001698523398394194 + 1 + + + 0.02999979083924905 + 9.34184479809901e-05 + 0.6825 + 0.4 + 0.010191140390365163 + 2 + + + 0.07499514611434314 + 0.000721848160011797 + 0.6825 + 0.6 + 0.025477850975912906 + 3 + + + 0.13996314734162235 + 0.0027342509940659386 + 0.6825 + 0.7999999999999999 + 0.04755865515503742 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.22478938318327918 + 0.008248760436198932 + 0.7962500000000002 + 0.9999999999999999 + 0.08850911276704647 + 5 + + + + 0.005000000000000001 + 0.0 + 0.70525 + 0.2 + 0.0017383678782225945 + 1 + + + 0.02999977450872196 + 9.682802642257415e-05 + 0.7280000000000001 + 0.4 + 0.010757435907153112 + 2 + + + 0.07499447333999151 + 0.000767143561222068 + 0.7507500000000001 + 0.6 + 0.027736324306012118 + 3 + + + 0.1399557241780807 + 0.0029789758168743885 + 0.7735000000000002 + 0.7999999999999999 + 0.05339692262603257 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.4489536845472877 + 0.026405182121175937 + 0.5687499999999998 + 1.9999999999999998 + 0.13170284550212794 + 5 + + + + 0.010000000000000002 + 0.0 + 0.65975 + 0.4 + 0.0033188179531993575 + 1 + + + 0.05999844844354342 + 0.0003604554514253385 + 0.6369999999999999 + 0.8 + 0.01930231419321288 + 2 + + + 0.1499659219918898 + 0.0027158133341141245 + 0.6142499999999999 + 1.2 + 0.04676833845214669 + 3 + + + 0.2797549653872151 + 0.010029538810157782 + 0.5914999999999998 + 1.5999999999999999 + 0.08459263276955759 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.4486714607971082 + 0.029509477978010346 + 0.6825 + 1.9999999999999998 + 0.15286710585547741 + 5 + + + + 0.010000000000000002 + 0.0 + 0.6825 + 0.4 + 0.003397046796788388 + 1 + + + 0.05999832672418815 + 0.00037366972477634184 + 0.6825 + 0.8 + 0.020382280780730327 + 2 + + + 0.14996117122135227 + 0.0028871012434149835 + 0.6825 + 1.2 + 0.05095570195182581 + 3 + + + 0.279705250321046 + 0.010932544800124837 + 0.6825 + 1.5999999999999999 + 0.09511731031007484 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.4483165583814953 + 0.032946477661669575 + 0.7962500000000002 + 1.9999999999999998 + 0.17701822553409294 + 5 + + + + 0.010000000000000002 + 0.0 + 0.70525 + 0.4 + 0.003476735756445189 + 1 + + + 0.05999819608166974 + 0.00038730754365645783 + 0.7280000000000001 + 0.8 + 0.021514871814306225 + 2 + + + 0.1499557897472335 + 0.003068218095906072 + 0.7507500000000001 + 1.2 + 0.055472648612024236 + 3 + + + 0.27964589882199553 + 0.011909976113905296 + 0.7735000000000002 + 1.5999999999999999 + 0.10679384525206514 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.6714717526514692 + 0.059324776317483355 + 0.5687499999999998 + 3.0 + 0.19755426825319194 + 5 + + + + 0.015000000000000003 + 0.0 + 0.65975 + 0.6000000000000001 + 0.004978226929799036 + 1 + + + 0.08999476354608112 + 0.0008110111763583676 + 0.6369999999999999 + 1.2000000000000002 + 0.02895347128981932 + 2 + + + 0.2248849965902175 + 0.006109687104432893 + 0.6142499999999999 + 1.8000000000000003 + 0.07015250767822004 + 3 + + + 0.4191732807571749 + 0.022553913418158388 + 0.5914999999999998 + 2.4000000000000004 + 0.1268889491543364 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.6705212655598021 + 0.06627041398307529 + 0.6825 + 3.0 + 0.2293006587832162 + 5 + + + + 0.015000000000000003 + 0.0 + 0.6825 + 0.6000000000000001 + 0.005095570195182582 + 1 + + + 0.08999435275148587 + 0.0008407416290982103 + 0.6825 + 1.2000000000000002 + 0.03057342117109549 + 2 + + + 0.22486896584579474 + 0.006494885173080899 + 0.6825 + 1.8000000000000003 + 0.07643355292773873 + 3 + + + 0.41900562239508304 + 0.024581511028308863 + 0.6825 + 2.4000000000000004 + 0.1426759654651123 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.6693267728327439 + 0.07394774516760211 + 0.7962500000000002 + 3.0 + 0.26552733830113945 + 5 + + + + 0.015000000000000003 + 0.0 + 0.70525 + 0.6000000000000001 + 0.005215103634667783 + 1 + + + 0.08999391184253919 + 0.0008714248657881436 + 0.7280000000000001 + 1.2000000000000002 + 0.03227230772145934 + 2 + + + 0.22485080742407032 + 0.006902155316010875 + 0.7507500000000001 + 1.8000000000000003 + 0.08320897291803635 + 3 + + + 0.41880550116507637 + 0.02677523107415042 + 0.7735000000000002 + 2.4000000000000004 + 0.16019076787809775 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.8916469160011646 + 0.1052503235783126 + 0.5687499999999998 + 3.9999999999999996 + 0.26340569100425587 + 5 + + + + 0.020000000000000004 + 0.0 + 0.65975 + 0.8 + 0.006637635906398715 + 1 + + + 0.11998758782779581 + 0.0014417638249571113 + 0.6369999999999999 + 1.6 + 0.03860462838642576 + 2 + + + 0.2997274320676728 + 0.010859443939231425 + 0.6142499999999999 + 2.4 + 0.09353667690429338 + 3 + + + 0.5580412734161713 + 0.04006462951038715 + 0.5914999999999998 + 3.1999999999999997 + 0.16918526553911517 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.8894005948952382 + 0.117501254833838 + 0.6825 + 3.9999999999999996 + 0.30573421171095483 + 5 + + + + 0.020000000000000004 + 0.0 + 0.6825 + 0.8 + 0.006794093593576776 + 1 + + + 0.11998661411976586 + 0.001494613825983552 + 0.6825 + 1.6 + 0.040764561561460654 + 2 + + + 0.29968944357228056 + 0.011543743529646582 + 0.6825 + 2.4 + 0.10191140390365162 + 3 + + + 0.5576442920925756 + 0.043658889479511645 + 0.6825 + 3.1999999999999997 + 0.19023462062014967 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 0.886580140629284 + 0.13101116958242834 + 0.7962500000000002 + 3.9999999999999996 + 0.3540364510681859 + 5 + + + + 0.020000000000000004 + 0.0 + 0.70525 + 0.8 + 0.006953471512890378 + 1 + + + 0.1199855690339639 + 0.0015491571835884771 + 0.7280000000000001 + 1.6 + 0.04302974362861245 + 2 + + + 0.29964641483643967 + 0.012267175271085104 + 0.7507500000000001 + 2.4 + 0.11094529722404847 + 3 + + + 0.5571705609529036 + 0.04754516312649003 + 0.7735000000000002 + 3.1999999999999997 + 0.2135876905041303 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 0.0 + 0.0 + 0 + + + 1.108710885528279 + 0.16402060840611415 + 0.5687499999999998 + 5.0 + 0.3292571137553198 + 5 + + + + 0.025 + 0.0 + 0.65975 + 1.0 + 0.008297044882998393 + 1 + + + 0.1499757578855052 + 0.0022526880319864895 + 0.6369999999999999 + 2.0 + 0.04825578548303219 + 2 + + + 0.3744677229691243 + 0.016963418065318883 + 0.6142499999999999 + 3.0 + 0.1169208461303667 + 3 + + + 0.6961766316554395 + 0.06253831529915599 + 0.5914999999999998 + 4.0 + 0.21148158192389394 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.6824999999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.7735 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.7507499999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.7279999999999999 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.7052499999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.9100000000000003 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.8190000000000001 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.8417500000000001 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.8645000000000002 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.8872500000000002 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.2247913998744051 + 0.008337941283247548 + 0.6824999999999998 + 0.9999999999999999 + 0.0832751286791252 + 5 + + + + 0.005000000000000001 + 0.0 + 0.7735 + 0.2 + 0.002087521566242444 + 1 + + + 0.0299996928207695 + 0.00011340429733766121 + 0.7507499999999999 + 0.4 + 0.012152548280367808 + 2 + + + 0.07499324046970797 + 0.0008551992089854935 + 0.7279999999999999 + 0.6 + 0.029479800346335447 + 3 + + + 0.13995128442185745 + 0.003162012645104311 + 0.7052499999999998 + 0.7999999999999999 + 0.053398028538165915 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.22473733416838887 + 0.009284118013790532 + 0.79625 + 0.9999999999999999 + 0.09610022938390472 + 5 + + + + 0.005000000000000001 + 0.0 + 0.79625 + 0.2 + 0.002135560652975661 + 1 + + + 0.029999669356162197 + 0.00011745516226770737 + 0.79625 + 0.4 + 0.012813363917853964 + 2 + + + 0.07499232699820373 + 0.0009075650112635905 + 0.79625 + 0.6 + 0.03203340979463491 + 3 + + + 0.1399417455433961 + 0.0034375139416580923 + 0.79625 + 0.7999999999999999 + 0.059795698283318495 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.22466756271931818 + 0.010360843331512843 + 0.9100000000000003 + 0.9999999999999999 + 0.11124385141138408 + 5 + + + + 0.005000000000000001 + 0.0 + 0.8190000000000001 + 0.2 + 0.0021847297949986826 + 1 + + + 0.029999643978823237 + 0.00012166996646248863 + 0.8417500000000001 + 0.4 + 0.013514921700462649 + 2 + + + 0.07499127797024227 + 0.0009637402869024222 + 0.8645000000000002 + 0.6 + 0.03484233748066644 + 3 + + + 0.13993013101791457 + 0.0037419705785554777 + 0.8872500000000002 + 0.7999999999999999 + 0.06708645656324928 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.44833258737774695 + 0.03330507108212044 + 0.6824999999999998 + 1.9999999999999998 + 0.1665502573582504 + 5 + + + + 0.010000000000000002 + 0.0 + 0.7735 + 0.4 + 0.004175043132484888 + 1 + + + 0.05999754258806525 + 0.000453609965566161 + 0.7507499999999999 + 0.8 + 0.024305096560735616 + 2 + + + 0.14994592817671185 + 0.003420320778288251 + 0.7279999999999999 + 1.2 + 0.058959600692670894 + 3 + + + 0.2796103980405985 + 0.012641335772585603 + 0.7052499999999998 + 1.5999999999999999 + 0.10679605707633183 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.447900933810649 + 0.0370696856626021 + 0.79625 + 1.9999999999999998 + 0.19220045876780945 + 5 + + + + 0.010000000000000002 + 0.0 + 0.79625 + 0.4 + 0.004271121305951322 + 1 + + + 0.05999735487477646 + 0.0004698125653843206 + 0.79625 + 0.8 + 0.02562672783570793 + 2 + + + 0.1499386217496273 + 0.0036296808972852653 + 0.79625 + 1.2 + 0.06406681958926982 + 3 + + + 0.2795341432242249 + 0.013741194242095092 + 0.79625 + 1.5999999999999999 + 0.11959139656663699 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.44734422158545123 + 0.04134709235154198 + 0.9100000000000003 + 1.9999999999999998 + 0.22248770282276817 + 5 + + + + 0.010000000000000002 + 0.0 + 0.8190000000000001 + 0.4 + 0.004369459589997365 + 1 + + + 0.059997151860234355 + 0.00048667081550714936 + 0.8417500000000001 + 0.8 + 0.027029843400925298 + 2 + + + 0.1499302313012302 + 0.0038542550946229098 + 0.8645000000000002 + 1.2 + 0.06968467496133288 + 3 + + + 0.27944131060155153 + 0.014956133928115838 + 0.8872500000000002 + 1.5999999999999999 + 0.13417291312649857 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.6693802839414613 + 0.07476156390856381 + 0.6824999999999998 + 3.0 + 0.24982538603737564 + 5 + + + + 0.015000000000000003 + 0.0 + 0.7735 + 0.6000000000000001 + 0.006262564698727333 + 1 + + + 0.08999170635795875 + 0.001020595333735172 + 0.7507499999999999 + 1.2000000000000002 + 0.03645764484110342 + 2 + + + 0.22481753245108538 + 0.0076939367883147435 + 0.7279999999999999 + 1.8000000000000003 + 0.08843940103900635 + 3 + + + 0.4186857831128397 + 0.028417838871381898 + 0.7052499999999998 + 2.4000000000000004 + 0.16019408561449777 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.6679283495818441 + 0.08315681968553448 + 0.79625 + 3.0 + 0.2883006881517143 + 5 + + + + 0.015000000000000003 + 0.0 + 0.79625 + 0.6000000000000001 + 0.006406681958926983 + 1 + + + 0.08999107284568783 + 0.0010570479587773502 + 0.79625 + 1.2000000000000002 + 0.0384400917535619 + 2 + + + 0.2247928808237873 + 0.008164610569052114 + 0.79625 + 1.8000000000000003 + 0.09610022938390475 + 3 + + + 0.41842873908599637 + 0.030884478751707856 + 0.79625 + 2.4000000000000004 + 0.17938709484995555 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.6660576351094187 + 0.09267079840101192 + 0.9100000000000003 + 3.0 + 0.33373155423415235 + 5 + + + + 0.015000000000000003 + 0.0 + 0.8190000000000001 + 0.6000000000000001 + 0.006554189384996047 + 1 + + + 0.08999038769506183 + 0.0010949753966944303 + 0.8417500000000001 + 1.2000000000000002 + 0.04054476510138795 + 2 + + + 0.22476457304461558 + 0.00866942676132477 + 0.8645000000000002 + 1.8000000000000003 + 0.10452701244199933 + 3 + + + 0.4181158987462338 + 0.03360728131035931 + 0.8872500000000002 + 2.4000000000000004 + 0.20125936968974792 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.8867050408003363 + 0.1324752314424904 + 0.6824999999999998 + 3.9999999999999996 + 0.3331005147165008 + 5 + + + + 0.020000000000000004 + 0.0 + 0.7735 + 0.8 + 0.008350086264969777 + 1 + + + 0.1199803414056062 + 0.0018143242849378773 + 0.7507499999999999 + 1.6 + 0.04861019312147123 + 2 + + + 0.2995675667969661 + 0.013673668217505593 + 0.7279999999999999 + 2.4 + 0.11791920138534179 + 3 + + + 0.556887106760069 + 0.05045801743636586 + 0.7052499999999998 + 3.1999999999999997 + 0.21359211415266366 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.8832796226530021 + 0.1472139643612257 + 0.79625 + 3.9999999999999996 + 0.3844009175356189 + 5 + + + + 0.020000000000000004 + 0.0 + 0.79625 + 0.8 + 0.008542242611902643 + 1 + + + 0.11997883981352 + 0.0018791209264494109 + 0.79625 + 1.6 + 0.05125345567141586 + 2 + + + 0.2995091584055708 + 0.014509460058983424 + 0.79625 + 2.4 + 0.12813363917853965 + 3 + + + 0.5562788647493105 + 0.05482317191245787 + 0.79625 + 3.1999999999999997 + 0.23918279313327398 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 0.0 + 0.0 + 0 + + + 0.8788724151895042 + 0.16385501973432015 + 0.9100000000000003 + 3.9999999999999996 + 0.44497540564553634 + 5 + + + + 0.020000000000000004 + 0.0 + 0.8190000000000001 + 0.8 + 0.00873891917999473 + 1 + + + 0.1199772158306062 + 0.0019465384612545893 + 0.8417500000000001 + 1.6 + 0.054059686801850595 + 2 + + + 0.2994420916079462 + 0.015405727507358226 + 0.8645000000000002 + 2.4 + 0.13936934992266575 + 3 + + + 0.555538874288481 + 0.05963685278451682 + 0.8872500000000002 + 3.1999999999999997 + 0.26834582625299713 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.7962499999999998 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.88725 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.8644999999999999 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.8417499999999999 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.8189999999999998 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 5 + + + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 1 + + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 2 + + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 3 + + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.22467075594616798 + 0.010473645624182319 + 0.7962499999999998 + 0.9999999999999999 + 0.10463165908413555 + 5 + + + + 0.005000000000000001 + 0.0 + 0.88725 + 0.2 + 0.0026259380114858795 + 1 + + + 0.029999514250250103 + 0.00014261207607094918 + 0.8644999999999999 + 0.4 + 0.015277071732958322 + 2 + + + 0.07498932128080589 + 0.001074954608801516 + 0.8417499999999999 + 0.6 + 0.037044285415939335 + 3 + + + 0.13992308592302755 + 0.003973111141197694 + 0.8189999999999998 + 0.7999999999999999 + 0.0670884307186679 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.22458390657116056 + 0.011682278296625825 + 0.91 + 0.9999999999999999 + 0.12096607597429732 + 5 + + + + 0.005000000000000001 + 0.0 + 0.91 + 0.2 + 0.002688135021651052 + 1 + + + 0.029999476112597838 + 0.00014784608265668405 + 0.91 + 0.4 + 0.016128810129906312 + 2 + + + 0.07498784274036484 + 0.0011423611219764272 + 0.91 + 0.6 + 0.04032202532476578 + 3 + + + 0.13990770567203425 + 0.004326424157233882 + 0.91 + 0.7999999999999999 + 0.07526778060622945 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.4473695057703564 + 0.041802023422185974 + 0.7962499999999998 + 1.9999999999999998 + 0.2092633181682711 + 5 + + + + 0.010000000000000002 + 0.0 + 0.88725 + 0.4 + 0.005251876022971759 + 1 + + + 0.059996114056781985 + 0.0005704339403441365 + 0.8644999999999999 + 0.8 + 0.030554143465916644 + 2 + + + 0.14991458127313056 + 0.004298873267299792 + 0.8417499999999999 + 1.2 + 0.07408857083187867 + 3 + + + 0.27938499309183823 + 0.01587912615448593 + 0.8189999999999998 + 1.5999999999999999 + 0.1341768614373358 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.4466769246220125 + 0.04659600529249324 + 0.91 + 1.9999999999999998 + 0.24193215194859463 + 5 + + + + 0.010000000000000002 + 0.0 + 0.91 + 0.4 + 0.005376270043302104 + 1 + + + 0.05999580896474667 + 0.0005913682084224609 + 0.91 + 0.8 + 0.032257620259812624 + 2 + + + 0.1499027563927144 + 0.0045682894904909834 + 0.91 + 1.2 + 0.08064405064953156 + 3 + + + 0.2792620943653187 + 0.017288027348150825 + 0.91 + 1.5999999999999999 + 0.1505355612124589 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.6661415024768195 + 0.09370825904641389 + 0.7962499999999998 + 3.0 + 0.3138949772524068 + 5 + + + + 0.015000000000000003 + 0.0 + 0.88725 + 0.6000000000000001 + 0.007877814034457638 + 1 + + + 0.0899868852497785 + 0.0012834225022680507 + 0.8644999999999999 + 1.2000000000000002 + 0.04583121519887497 + 2 + + + 0.2247117738122038 + 0.00966892126630877 + 0.8417499999999999 + 1.8000000000000003 + 0.11113285624781802 + 3 + + + 0.4179260702322364 + 0.03567813336601905 + 0.8189999999999998 + 2.4000000000000004 + 0.20126529215600375 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.6638164577855938 + 0.10434335968929515 + 0.91 + 3.0 + 0.362898227922892 + 5 + + + + 0.015000000000000003 + 0.0 + 0.91 + 0.6000000000000001 + 0.008064405064953156 + 1 + + + 0.08998585561581139 + 0.0013305180122235613 + 0.91 + 1.2000000000000002 + 0.04838643038971893 + 2 + + + 0.224671884203331 + 0.010274321232796675 + 0.91 + 1.8000000000000003 + 0.12096607597429734 + 3 + + + 0.4175120921407201 + 0.038831872566114006 + 0.91 + 2.4000000000000004 + 0.22580334181868836 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.8790663688345872 + 0.16573356464997913 + 0.7962499999999998 + 3.9999999999999996 + 0.4185266363365422 + 5 + + + + 0.020000000000000004 + 0.0 + 0.88725 + 0.8 + 0.010503752045943518 + 1 + + + 0.11996891420720188 + 0.0022815059484816353 + 0.8644999999999999 + 1.6 + 0.06110828693183329 + 2 + + + 0.2993170029353888 + 0.017180376738322095 + 0.8417499999999999 + 2.4 + 0.14817714166375734 + 3 + + + 0.5550897160958808 + 0.06330375837058227 + 0.8189999999999998 + 3.1999999999999997 + 0.2683537228746716 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 0.0 + 0.0 + 0 + + + 0.873596176933592 + 0.18426629722259286 + 0.91 + 3.9999999999999996 + 0.48386430389718926 + 5 + + + + 0.020000000000000004 + 0.0 + 0.91 + 0.8 + 0.010752540086604208 + 1 + + + 0.11996647376475575 + 0.002365214890733759 + 0.91 + 1.6 + 0.06451524051962525 + 2 + + + 0.29922251401859423 + 0.018254686958268977 + 0.91 + 2.4 + 0.16128810129906312 + 3 + + + 0.554111102253146 + 0.06886996730855413 + 0.91 + 3.1999999999999997 + 0.3010711224249178 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.2750000000000001 + 0.0 + 0.0 + 1.3877787807814457e-16 + 0.0 + 5 + + + + 0.095 + 0.0 + 0.0 + 0.8 + 0.0 + 1 + + + 0.17 + 0.0 + 0.0 + 0.6000000000000001 + 0.0 + 2 + + + 0.22500000000000003 + 0.0 + 0.0 + 0.40000000000000013 + 0.0 + 3 + + + 0.26000000000000006 + 0.0 + 0.0 + 0.20000000000000015 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.2749997392296748 + 0.00024331172271600116 + 0.11374999999999999 + 1.3877787807814457e-16 + 0.003927171966043691 + 5 + + + + 0.095 + 0.0 + 0.022750000000000003 + 0.8 + 0.00021394297541588826 + 1 + + + 0.1699999929029661 + 2.9359452045949326e-05 + 0.045500000000000006 + 0.6000000000000001 + 0.001093707868886913 + 2 + + + 0.22499994032419598 + 0.00010378545923522828 + 0.06825 + 0.40000000000000013 + 0.002259493880770755 + 3 + + + 0.25999982916738856 + 0.00019143831150623524 + 0.091 + 0.20000000000000015 + 0.0033311077034465625 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.49999999999999994 + 0.0 + 0.0 + 1.0 + 0.0 + 5 + + + + 0.1 + 0.0 + 0.0 + 1.0 + 0.0 + 1 + + + 0.2 + 0.0 + 0.0 + 1.0 + 0.0 + 2 + + + 0.3 + 0.0 + 0.0 + 1.0 + 0.0 + 3 + + + 0.39999999999999997 + 0.0 + 0.0 + 1.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.4999959047514427 + 0.0014277010884732031 + 0.11374999999999999 + 1.0 + 0.010717512499764374 + 5 + + + + 0.1 + 0.0 + 0.022750000000000003 + 1.0 + 0.00023771441712876467 + 1 + + + 0.19999998587077045 + 4.754595675579038e-05 + 0.045500000000000006 + 1.0 + 0.0014265942130073247 + 2 + + + 0.29999979361143686 + 0.0002377789089917519 + 0.06825 + 1.0 + 0.0035678715679734454 + 3 + + + 0.3999988512912527 + 0.0006659868280316737 + 0.091 + 1.0 + 0.006663769776296825 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.7250000000000003 + 0.0 + 0.0 + 2.000000000000001 + 0.0 + 5 + + + + 0.10500000000000001 + 0.0 + 0.0 + 1.2000000000000002 + 0.0 + 1 + + + 0.23000000000000004 + 0.0 + 0.0 + 1.4000000000000004 + 0.0 + 2 + + + 0.37500000000000006 + 0.0 + 0.0 + 1.6000000000000005 + 0.0 + 3 + + + 0.5400000000000001 + 0.0 + 0.0 + 1.8000000000000007 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.7249833152337468 + 0.0035990120790727223 + 0.11374999999999999 + 2.000000000000001 + 0.017507853033485066 + 5 + + + + 0.10500000000000001 + 0.0 + 0.022750000000000003 + 1.2000000000000002 + 0.0002614858588416412 + 1 + + + 0.22999997544745768 + 6.977397429320304e-05 + 0.045500000000000006 + 1.4000000000000004 + 0.0017594805571277369 + 2 + + + 0.3749995086842722 + 0.000424802923301777 + 0.06825 + 1.6000000000000005 + 0.004876249255176138 + 3 + + + 0.5399963777245322 + 0.0014236456304365177 + 0.091 + 1.8000000000000007 + 0.009996431849147093 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.95 + 0.0 + 0.0 + 3.0000000000000004 + 0.0 + 5 + + + + 0.11 + 0.0 + 0.0 + 1.4 + 0.0 + 1 + + + 0.26 + 0.0 + 0.0 + 1.7999999999999998 + 0.0 + 2 + + + 0.44999999999999996 + 0.0 + 0.0 + 2.1999999999999997 + 0.0 + 3 + + + 0.6799999999999999 + 0.0 + 0.0 + 2.6 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 0.9499567600988262 + 0.006757183026665975 + 0.11374999999999999 + 3.0000000000000004 + 0.02429819356720574 + 5 + + + + 0.11 + 0.0 + 0.022750000000000003 + 1.4 + 0.0002852573005545176 + 1 + + + 0.25999996098022715 + 9.604350406535741e-05 + 0.045500000000000006 + 1.7999999999999998 + 0.002092366901248148 + 2 + + + 0.449999040062757 + 0.0006648573616571141 + 0.06825 + 2.1999999999999997 + 0.006184626942378826 + 3 + + + 0.6799917165759332 + 0.0024644101037097996 + 0.091 + 2.6 + 0.01332909392199735 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.175 + 0.0 + 0.0 + 3.999999999999999 + 0.0 + 5 + + + + 0.115 + 0.0 + 0.0 + 1.6 + 0.0 + 1 + + + 0.29000000000000004 + 0.0 + 0.0 + 2.2 + 0.0 + 2 + + + 0.525 + 0.0 + 0.0 + 2.8 + 0.0 + 3 + + + 0.8200000000000001 + 0.0 + 0.0 + 3.3999999999999995 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.174911029183023 + 0.010902123975270399 + 0.11374999999999999 + 3.999999999999999 + 0.03108853410092642 + 5 + + + + 0.115 + 0.0 + 0.022750000000000003 + 1.6 + 0.0003090287422673941 + 1 + + + 0.28999994181627864 + 0.00012635454537810925 + 0.045500000000000006 + 2.2 + 0.00242525324536856 + 2 + + + 0.5249983422670846 + 0.0009579420441781414 + 0.06825 + 2.8 + 0.007493004629581518 + 3 + + + 0.8199841759678946 + 0.003788273903183332 + 0.091 + 3.3999999999999995 + 0.016661755994847614 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.4 + 0.0 + 0.0 + 5.0 + 0.0 + 5 + + + + 0.12 + 0.0 + 0.0 + 1.7999999999999998 + 0.0 + 1 + + + 0.31999999999999995 + 0.0 + 0.0 + 2.5999999999999996 + 0.0 + 2 + + + 0.6 + 0.0 + 0.0 + 3.3999999999999995 + 0.0 + 3 + + + 0.96 + 0.0 + 0.0 + 4.199999999999999 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.3998409128910851 + 0.01603371668344733 + 0.11374999999999999 + 5.0 + 0.0378788746346471 + 5 + + + + 0.12 + 0.0 + 0.022750000000000003 + 1.7999999999999998 + 0.00033280018398027054 + 1 + + + 0.3199999173028119 + 0.00016070709743599946 + 0.045500000000000006 + 2.5999999999999996 + 0.0027581395894889713 + 2 + + + 0.59999736981762 + 0.0013040567516139317 + 0.06825 + 3.3999999999999995 + 0.008801382316784206 + 3 + + + 0.9599730640409094 + 0.005395228954571226 + 0.091 + 4.199999999999999 + 0.01999441806769787 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.625 + 0.0 + 0.0 + 5.997113636363636 + 0.0 + 5 + + + + 0.125 + 0.0 + 0.0 + 2.0 + 0.0 + 1 + + + 0.35 + 0.0 + 0.0 + 3.0 + 0.0 + 2 + + + 0.675 + 0.0 + 0.0 + 4.0 + 0.0 + 3 + + + 1.1 + 0.0 + 0.0 + 5.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 1.0 + 0.0 + 0 + + + 1.6247412023504562 + 0.022151814627819844 + 0.11374999999999999 + 5.997113636363636 + 0.04466921516836779 + 5 + + + + 0.125 + 0.0 + 0.022750000000000003 + 2.0 + 0.00035657162569314706 + 1 + + + 0.34999988678702687 + 0.0001991011593422548 + 0.045500000000000006 + 3.0 + 0.0030910259336093837 + 2 + + + 0.6749960772349328 + 0.0017032012253424154 + 0.06825 + 4.0 + 0.0101097600039869 + 3 + + + 1.0999576889578446 + 0.007285265454020149 + 0.091 + 5.0 + 0.023327080140548143 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.2749954661432657 + 0.0013301896602762164 + 3.469446951953614e-18 + 1.3877787807814457e-16 + 0.00917768774859164 + 5 + + + + 0.09499987176295961 + 0.00010743052262039315 + 0.09100000000000001 + 0.8 + 0.00431950575373839 + 1 + + + 0.16999890072695273 + 0.00048478494926445007 + 0.06825000000000002 + 0.6000000000000001 + 0.007012243900316188 + 2 + + + 0.22499738908499134 + 0.0008918812633241006 + 0.04550000000000001 + 0.40000000000000013 + 0.008464212066868102 + 3 + + + 0.25999608593539536 + 0.0011938337745739198 + 0.022750000000000006 + 0.20000000000000015 + 0.009058818234166698 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.2749932385409322 + 0.0015756274640406109 + 0.11375 + 1.3877787807814457e-16 + 0.013130409681790248 + 5 + + + + 0.09499987176295961 + 0.00010743052262039315 + 0.11375 + 0.8 + 0.004535959708254813 + 1 + + + 0.16999873316320882 + 0.0005144710383138844 + 0.11375 + 0.6000000000000001 + 0.008116980530561244 + 2 + + + 0.2249966050113583 + 0.0009967088733889185 + 0.11375 + 0.40000000000000013 + 0.010743062466919294 + 3 + + + 0.25999442457598315 + 0.001387032008113093 + 0.11375 + 0.20000000000000015 + 0.012414205517328962 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.27499045308122044 + 0.0018231487903233364 + 0.22749999999999998 + 1.3877787807814457e-16 + 0.01713494501844694 + 5 + + + + 0.09499987176295961 + 0.00010743052262039315 + 0.1365 + 0.8 + 0.004752976989844377 + 1 + + + 0.1699985503512771 + 0.000544269405896832 + 0.15925 + 0.6000000000000001 + 0.00922823002303631 + 2 + + + 0.22499569319225493 + 0.0011021563892465005 + 0.182 + 0.40000000000000013 + 0.013042283020588671 + 3 + + + 0.25999239777619215 + 0.0015816960930095222 + 0.20475 + 0.20000000000000015 + 0.015808244001705767 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.49998012492637617 + 0.00393352893335815 + 3.469446951953614e-18 + 1.0 + 0.01310485971463533 + 5 + + + + 0.09999985751439958 + 0.00011936724735599238 + 0.09100000000000001 + 1.0 + 0.004534190035834771 + 1 + + + 0.19999830635589416 + 0.000668128242374378 + 0.06825000000000002 + 1.0 + 0.00810854454487395 + 2 + + + 0.2999943888161961 + 0.0015503932057221452 + 0.04550000000000001 + 1.0 + 0.01072679215762019 + 3 + + + 0.39998810273365065 + 0.0026706225307323384 + 0.022750000000000006 + 1.0 + 0.012391654933946238 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.4999593926222201 + 0.005371301627498765 + 0.11375 + 1.0 + 0.023873472148709537 + 5 + + + + 0.09999985751439958 + 0.00011936724735599238 + 0.11375 + 1.0 + 0.004774694429741908 + 1 + + + 0.1999980052072785 + 0.0007162000825170494 + 0.11375 + 1.0 + 0.009549388859483816 + 2 + + + 0.2999921633545065 + 0.001790484899088978 + 0.11375 + 1.0 + 0.014324083289225725 + 3 + + + 0.3999800523229055 + 0.003342197205887934 + 0.11375 + 1.0 + 0.019098777718967633 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.49992994437528177 + 0.006825856775020102 + 0.22749999999999998 + 1.0 + 0.034821303866024056 + 5 + + + + 0.09999985751439958 + 0.00011936724735599238 + 0.1365 + 1.0 + 0.005015824742619203 + 1 + + + 0.1999976737876913 + 0.0007644595261926746 + 0.15925 + 1.0 + 0.010999000666622263 + 2 + + + 0.29998949760507715 + 0.002032137790394564 + 0.182 + 1.0 + 0.017955850909925738 + 3 + + + 0.39996955515233934 + 0.004019879471682369 + 0.20475 + 1.0 + 0.025893779607659526 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.7249500007870421 + 0.007621092653192513 + 3.469446951953614e-18 + 2.000000000000001 + 0.017032031680679027 + 5 + + + + 0.10499984326583953 + 0.00013130397209159162 + 0.09100000000000001 + 1.2000000000000002 + 0.004748874317931154 + 1 + + + 0.2299975572695087 + 0.0008736466079658454 + 0.06825000000000002 + 1.4000000000000004 + 0.009204845189431715 + 2 + + + 0.3749898838981268 + 0.0023583090561567167 + 0.04550000000000001 + 1.6000000000000005 + 0.01298937224837228 + 3 + + + 0.5399741851108504 + 0.004630883337326863 + 0.022750000000000006 + 1.8000000000000007 + 0.015724491633725784 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.7248793855431308 + 0.011243436691955612 + 0.11375 + 2.000000000000001 + 0.034616534615628844 + 5 + + + + 0.10499984326583953 + 0.00013130397209159162 + 0.11375 + 1.2000000000000002 + 0.005013429151229003 + 1 + + + 0.2299970720740931 + 0.0009441891414215774 + 0.11375 + 1.4000000000000004 + 0.01098179718840639 + 2 + + + 0.37498515702656116 + 0.002787169002821696 + 0.11375 + 1.6000000000000005 + 0.017905104111532157 + 3 + + + 0.5399522757430398 + 0.00606596861296369 + 0.11375 + 1.8000000000000007 + 0.02578334992060631 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.7247733506230982 + 0.014911125592853302 + 0.22749999999999998 + 2.000000000000001 + 0.0525076627136012 + 5 + + + + 0.10499984326583953 + 0.00013130397209159162 + 0.1365 + 1.2000000000000002 + 0.005278672495394027 + 1 + + + 0.22999653438561785 + 0.001015012683972279 + 0.15925 + 1.4000000000000004 + 0.012769771310208218 + 2 + + + 0.3749793842579571 + 0.003218947869238803 + 0.182 + 1.6000000000000005 + 0.02286941879926281 + 3 + + + 0.5399226687017853 + 0.007514928212151949 + 0.20475 + 1.8000000000000007 + 0.035979315213613305 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.9499002981883484 + 0.01239280630030078 + 3.469446951953614e-18 + 3.0000000000000004 + 0.02095920364672271 + 5 + + + + 0.10999982901727948 + 0.00014324069682719086 + 0.09100000000000001 + 1.4 + 0.0049635586000275345 + 1 + + + 0.2599966360974126 + 0.001101339919154619 + 0.06825000000000002 + 1.7999999999999998 + 0.010301145833989476 + 2 + + + 0.4499835762793772 + 0.0033156255314062185 + 0.04550000000000001 + 2.1999999999999997 + 0.015251952339124365 + 3 + + + 0.6799527314225401 + 0.007074594120951799 + 0.022750000000000006 + 2.6 + 0.019057328333505315 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.9497335224021967 + 0.019191499446811984 + 0.11375 + 3.0000000000000004 + 0.045359597082548116 + 5 + + + + 0.10999982901727948 + 0.00014324069682719086 + 0.11375 + 1.4 + 0.005252163872716098 + 1 + + + 0.25999590897198444 + 0.001198438011204236 + 0.11375 + 1.7999999999999998 + 0.012414205517328959 + 2 + + + 0.4499750107281031 + 0.003986753077832196 + 0.11375 + 2.1999999999999997 + 0.02148612493383858 + 3 + + + 0.6799067271491585 + 0.009558257320839968 + 0.11375 + 2.6 + 0.03246792212224497 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 0.9494750927917609 + 0.026077174374200054 + 0.22749999999999998 + 3.0000000000000004 + 0.07019402156117831 + 5 + + + + 0.10999982901727948 + 0.00014324069682719086 + 0.1365 + 1.4 + 0.005541520248168851 + 1 + + + 0.2599950985551531 + 0.0012959285721181467 + 0.15925 + 1.7999999999999998 + 0.01454054195379417 + 2 + + + 0.44996440462470977 + 0.0046625702974665475 + 0.182 + 2.1999999999999997 + 0.02778298668859987 + 3 + + + 0.6798431450164052 + 0.012066609400568421 + 0.20475 + 2.6 + 0.04606485081956705 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.1748262219472618 + 0.01824857506232914 + 3.469446951953614e-18 + 3.999999999999999 + 0.0248863756127664 + 5 + + + + 0.11499981476871944 + 0.0001551774215627901 + 0.09100000000000001 + 1.6 + 0.005178242882123917 + 1 + + + 0.2899955254693219 + 0.001351208035954427 + 0.06825000000000002 + 2.2 + 0.011397446478547239 + 2 + + + 0.5249751679154893 + 0.0044223387659727475 + 0.04550000000000001 + 2.8 + 0.017514532429876453 + 3 + + + 0.8199221401030579 + 0.010001727651769246 + 0.022750000000000006 + 3.3999999999999995 + 0.02239016503328486 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.1745021142381133 + 0.029214769949319083 + 0.11375 + 3.999999999999999 + 0.05610265954946741 + 5 + + + + 0.11499981476871944 + 0.0001551774215627901 + 0.11375 + 1.6 + 0.005490898594203195 + 1 + + + 0.28999449110947817 + 0.0014789464654558161 + 0.11375 + 2.2 + 0.013846613846251535 + 2 + + + 0.5249611491847094 + 0.005389227399202037 + 0.11375 + 2.8 + 0.025067145756145017 + 3 + + + 0.819839039427756 + 0.013818949657407681 + 0.11375 + 3.3999999999999995 + 0.03915249432388364 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.173989623721886 + 0.04032153991755775 + 0.22749999999999998 + 3.999999999999999 + 0.08788038040875541 + 5 + + + + 0.11499981476871944 + 0.0001551774215627901 + 0.1365 + 1.6 + 0.005804368000943676 + 1 + + + 0.28999333270673655 + 0.001607206847617104 + 0.15925 + 2.2 + 0.016311312597380122 + 2 + + + 0.5249436102456081 + 0.006362985249750528 + 0.182 + 2.8 + 0.03269655457793694 + 3 + + + 0.81972239288738 + 0.017674619710410646 + 0.20475 + 3.3999999999999995 + 0.05615038642552082 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.399722977318397 + 0.025188283835668235 + 3.469446951953614e-18 + 5.0 + 0.028813547578810085 + 5 + + + + 0.11999980052015939 + 0.0001671141462983893 + 0.09100000000000001 + 1.7999999999999998 + 0.005392927164220298 + 1 + + + 0.31999420801506145 + 0.0016232508052770277 + 0.06825000000000002 + 2.5999999999999996 + 0.012493747123104998 + 2 + + + 0.5999643607700726 + 0.00567844431209645 + 0.04550000000000001 + 3.3999999999999995 + 0.019777112520628536 + 3 + + + 0.9598808096818615 + 0.01341225154378296 + 0.022750000000000006 + 4.199999999999999 + 0.025723001733064396 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.3991654797951716 + 0.04131234158899406 + 0.11375 + 5.0 + 0.0668457220163867 + 5 + + + + 0.11999980052015939 + 0.0001671141462983893 + 0.11375 + 1.7999999999999998 + 0.0057296333156902895 + 1 + + + 0.31999279369531347 + 0.0017857142551813057 + 0.11375 + 2.5999999999999996 + 0.015279022175174104 + 2 + + + 0.5999429971514529 + 0.006994580623924559 + 0.11375 + 3.3999999999999995 + 0.028648166578451446 + 3 + + + 0.9597448461787237 + 0.018847907190569283 + 0.11375 + 4.199999999999999 + 0.04583706652552231 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.3982714383581485 + 0.05764107724407508 + 0.22749999999999998 + 5.0 + 0.10556673925633255 + 5 + + + + 0.11999980052015939 + 0.0001671141462983893 + 0.1365 + 1.7999999999999998 + 0.006067215753718501 + 1 + + + 0.3199912032511871 + 0.0019488471315606674 + 0.15925 + 2.5999999999999996 + 0.018082083240966076 + 2 + + + 0.5999160527401424 + 0.00832016940401302 + 0.182 + 3.3999999999999995 + 0.037610122467274 + 3 + + + 0.9595518238808469 + 0.02433858542277236 + 0.20475 + 4.199999999999999 + 0.06623592203147458 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.624585770077778 + 0.033211797227413346 + 3.469446951953614e-18 + 5.997113636363636 + 0.032740719544853775 + 5 + + + + 0.12499978627159936 + 0.00017905087103398858 + 0.09100000000000001 + 2.0 + 0.00560761144631668 + 1 + + + 0.3499926663645755 + 0.0019174680609323003 + 0.06825000000000002 + 3.0 + 0.01359004776766276 + 2 + + + 0.6749508568159275 + 0.007083937139772059 + 0.04550000000000001 + 4.0 + 0.022039692611380626 + 3 + + + 1.0998271387998595 + 0.017306128255163446 + 0.022750000000000006 + 5.0 + 0.029055838432843935 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.62370394728801 + 0.05548312116866856 + 0.11375 + 5.997113636363636 + 0.077588784483306 + 5 + + + + 0.12499978627159936 + 0.00017905087103398858 + 0.11375 + 2.0 + 0.005968368037177384 + 1 + + + 0.34999079193846305 + 0.002118741108800089 + 0.11375 + 3.0 + 0.016711430504096677 + 2 + + + 0.6749199794174044 + 0.008802799790992664 + 0.11375 + 4.0 + 0.03222918740075788 + 3 + + + 1.099619781855003 + 0.024644966732642264 + 0.11375 + 5.0 + 0.05252163872716099 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 1.0 + 0.0 + 0 + + + 1.622275083970389 + 0.07803196030516615 + 0.22749999999999998 + 5.997113636363636 + 0.12325309810390968 + 5 + + + + 0.12499978627159936 + 0.00017905087103398858 + 0.1365 + 2.0 + 0.006330063506493326 + 1 + + + 0.34998867659974076 + 0.002320849009145451 + 0.15925 + 3.0 + 0.019852853884552032 + 2 + + + 0.6748807838197816 + 0.010534095941736047 + 0.182 + 4.0 + 0.04252369035661108 + 3 + + + 1.09932285291337 + 0.03205806245132944 + 0.20475 + 5.0 + 0.07632145763742836 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.2749771800221946 + 0.002938666793181615 + 0.11375000000000005 + 1.3877787807814457e-16 + 0.022524194283146677 + 5 + + + + 0.0949994733963638 + 0.00021770174539272326 + 0.20475000000000002 + 0.8 + 0.008967069949955152 + 1 + + + 0.16999515767116025 + 0.0010117215640298386 + 0.18200000000000002 + 0.6000000000000001 + 0.01530313216302787 + 2 + + + 0.2249877683750685 + 0.0019110405135396636 + 0.15925000000000003 + 0.40000000000000013 + 0.019410912135958226 + 3 + + + 0.25998077048976653 + 0.002610513386266869 + 0.13650000000000004 + 0.20000000000000015 + 0.021687286757592274 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.27497223483286143 + 0.0031927908305124514 + 0.2275 + 1.3877787807814457e-16 + 0.026608094895632522 + 5 + + + + 0.0949994733963638 + 0.00021770174539272326 + 0.2275 + 0.8 + 0.009191887327582141 + 1 + + + 0.16999479778642143 + 0.00104253450921875 + 0.2275 + 0.6000000000000001 + 0.016448640480936465 + 2 + + + 0.22498605872704935 + 0.0020197248224381827 + 0.2275 + 0.40000000000000013 + 0.02177025946006297 + 3 + + + 0.2599771050769682 + 0.0028106432220847623 + 0.2275 + 0.20000000000000015 + 0.02515674426496166 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.27496661411250306 + 0.0034513051232238382 + 0.3412500000000002 + 1.3877787807814457e-16 + 0.030801217594081342 + 5 + + + + 0.0949994733963638 + 0.00021770174539272326 + 0.25025000000000003 + 0.8 + 0.009417891951842146 + 1 + + + 0.16999441923610858 + 0.0010735840693250663 + 0.2730000000000001 + 0.6000000000000001 + 0.017607875474479295 + 2 + + + 0.22498419413448126 + 0.002129715431552055 + 0.2957500000000001 + 0.40000000000000013 + 0.0241725416430847 + 3 + + + 0.25997299718972583 + 0.003013861846162533 + 0.31850000000000017 + 0.20000000000000015 + 0.028707673506622358 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.49988093236773395 + 0.009397400312802368 + 0.11375000000000005 + 1.0 + 0.037271792086722655 + 5 + + + + 0.09999941488484868 + 0.00024189082821413695 + 0.20475000000000002 + 1.0 + 0.009425873784886886 + 1 + + + 0.19999245667049206 + 0.0014014237874549907 + 0.18200000000000002 + 1.0 + 0.01785746467369831 + 2 + + + 0.2999727093002805 + 0.0033793287975782665 + 0.15925000000000003 + 1.0 + 0.02530385987596511 + 3 + + + 0.3999361693381711 + 0.0060771975419239115 + 0.13650000000000004 + 1.0 + 0.03177301569507652 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.4998332593538293 + 0.010883219143414953 + 0.2275 + 1.0 + 0.048378354355695485 + 5 + + + + 0.09999941488484868 + 0.00024189082821413695 + 0.2275 + 1.0 + 0.009675670871139096 + 1 + + + 0.1999918084837417 + 0.0014513166626196118 + 0.2275 + 1.0 + 0.01935134174227819 + 2 + + + 0.2999678197211303 + 0.003628164279338098 + 0.2275 + 1.0 + 0.029027012613417287 + 3 + + + 0.39991808905514764 + 0.006772229886518387 + 0.2275 + 1.0 + 0.03870268348455638 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.49977516940161726 + 0.012404380888817772 + 0.3412500000000002 + 1.0 + 0.05986273769997428 + 5 + + + + 0.09999941488484868 + 0.00024189082821413695 + 0.25025000000000003 + 1.0 + 0.00992678712031688 + 1 + + + 0.19999112350412065 + 0.0015016048824178223 + 0.2730000000000001 + 1.0 + 0.02086369742557965 + 2 + + + 0.299962400759029 + 0.0038802892356599814 + 0.2957500000000001 + 1.0 + 0.03282283310208295 + 3 + + + 0.3998970784830015 + 0.007480128209435322 + 0.31850000000000017 + 1.0 + 0.04581759353595552 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.7246698836981529 + 0.01903807813106806 + 0.11375000000000005 + 2.000000000000001 + 0.05201938989029866 + 5 + + + + 0.10499935637333353 + 0.00026607991103555067 + 0.20475000000000002 + 1.2000000000000002 + 0.00988467761981862 + 1 + + + 0.22998902279751993 + 0.0018400976170485019 + 0.18200000000000002 + 1.4000000000000004 + 0.020411797184368755 + 2 + + + 0.374949488571663 + 0.005203305922530594 + 0.15925000000000003 + 1.6000000000000005 + 0.031196807615972003 + 3 + + + 0.5398537402002987 + 0.010806135653147165 + 0.13650000000000004 + 1.8000000000000007 + 0.04185874463256078 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.7245047769492078 + 0.022778144713937343 + 0.2275 + 2.000000000000001 + 0.07014861381575846 + 5 + + + + 0.10499935637333353 + 0.00026607991103555067 + 0.2275 + 1.2000000000000002 + 0.01015945441469605 + 1 + + + 0.2299879766491305 + 0.0019133083098465625 + 0.2275 + 1.4000000000000004 + 0.02225404300361992 + 2 + + + 0.37493904981806514 + 0.005647682986924517 + 0.2275 + 1.6000000000000005 + 0.036283765766771614 + 3 + + + 0.5398040375155101 + 0.01229060443601611 + 0.2275 + 1.8000000000000007 + 0.05224862270415113 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.7242976185700228 + 0.026613615440359756 + 0.3412500000000002 + 2.000000000000001 + 0.08892425780586727 + 5 + + + + 0.10499935637333353 + 0.00026607991103555067 + 0.25025000000000003 + 1.2000000000000002 + 0.010435682288791614 + 1 + + + 0.22998686703173235 + 0.0019871111684931055 + 0.2730000000000001 + 1.4000000000000004 + 0.024119519376680006 + 2 + + + 0.3749273603571664 + 0.006098209395454933 + 0.2957500000000001 + 1.6000000000000005 + 0.041473124561081216 + 3 + + + 0.5397451708384106 + 0.013804288067376628 + 0.31850000000000017 + 1.8000000000000007 + 0.06292751356528871 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.9492997488374295 + 0.03185880387265031 + 0.11375000000000005 + 3.0000000000000004 + 0.06676698769387462 + 5 + + + + 0.10999929786181839 + 0.00029026899385696433 + 0.20475000000000002 + 1.4 + 0.010343481454750354 + 1 + + + 0.2599847705416706 + 0.0023277417094661077 + 0.18200000000000002 + 1.7999999999999998 + 0.022966129695039195 + 2 + + + 0.4499163735123284 + 0.007382927939376903 + 0.15925000000000003 + 2.1999999999999997 + 0.03708975535597888 + 3 + + + 0.6797220670988493 + 0.01679693480515232 + 0.13650000000000004 + 2.6 + 0.05194447357004501 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.9489060056281371 + 0.03887313222219823 + 0.2275 + 3.0000000000000004 + 0.0919188732758214 + 5 + + + + 0.10999929786181839 + 0.00029026899385696433 + 0.2275 + 1.4 + 0.010643237958253005 + 1 + + + 0.2599832004864869 + 0.0024285077548248093 + 0.2275 + 1.7999999999999998 + 0.025156744264961648 + 2 + + + 0.44989738729137335 + 0.008078213491216797 + 0.2275 + 2.1999999999999997 + 0.04354051892012593 + 3 + + + 0.6796170263615202 + 0.01936502717837944 + 0.2275 + 2.6 + 0.06579456192374585 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 0.9484038827526899 + 0.046070229495298085 + 0.3412500000000002 + 3.0000000000000004 + 0.11798577791176017 + 5 + + + + 0.10999929786181839 + 0.00029026899385696433 + 0.25025000000000003 + 1.4 + 0.010944577457266345 + 1 + + + 0.2599815301298425 + 0.0025301008183436797 + 0.2730000000000001 + 1.7999999999999998 + 0.02737534132778035 + 2 + + + 0.4498759699655252 + 0.00878337716882951 + 0.2957500000000001 + 2.1999999999999997 + 0.050123416020079456 + 3 + + + 0.6794911375039625 + 0.021985078290553465 + 0.31850000000000017 + 2.6 + 0.08003743359462184 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.1737262726558986 + 0.047857073983893474 + 0.11375000000000005 + 3.999999999999999 + 0.08151458549745061 + 5 + + + + 0.11499923935030326 + 0.00031445807667837805 + 0.20475000000000002 + 1.6 + 0.010802285289682086 + 1 + + + 0.2899796143947275 + 0.002864354577409252 + 0.18200000000000002 + 2.2 + 0.025520462205709634 + 2 + + + 0.5248716316757884 + 0.009918142569892572 + 0.15925000000000003 + 2.8 + 0.042982703095985765 + 3 + + + 0.8195297380111859 + 0.02404910006977406 + 0.13650000000000004 + 3.3999999999999995 + 0.06203020250752926 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.172956263513369 + 0.05916219495128954 + 0.2275 + 3.999999999999999 + 0.11368913273588438 + 5 + + + + 0.11499923935030326 + 0.00031445807667837805 + 0.2275 + 1.6 + 0.01112702150180996 + 1 + + + 0.28997737820297614 + 0.0029969131135496718 + 0.2275 + 2.2 + 0.028059445526303385 + 2 + + + 0.5248404708360316 + 0.010919674877569297 + 0.2275 + 2.8 + 0.05079727207348026 + 3 + + + 0.819339141168631 + 0.027994552523733514 + 0.2275 + 3.3999999999999995 + 0.0793405011433406 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.1719641432545673 + 0.07076219950313639 + 0.3412500000000002 + 3.999999999999999 + 0.14704729801765315 + 5 + + + + 0.11499923935030326 + 0.00031445807667837805 + 0.25025000000000003 + 1.6 + 0.01145347262574108 + 1 + + + 0.28997499311377645 + 0.0031305714821340406 + 0.2730000000000001 + 2.2 + 0.03063116327888071 + 2 + + + 0.5248051273393148 + 0.011935673298656944 + 0.2957500000000001 + 2.8 + 0.058773707479077716 + 3 + + + 0.8191088621864332 + 0.03202086661959517 + 0.31850000000000017 + 3.3999999999999995 + 0.09714735362395503 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.3979052383194612 + 0.06702977819564801 + 0.11375000000000005 + 5.0 + 0.0962621833010266 + 5 + + + + 0.11999918083878813 + 0.0003386471594997917 + 0.20475000000000002 + 1.7999999999999998 + 0.01126108912461382 + 1 + + + 0.31997346885106537 + 0.0034499345896290643 + 0.18200000000000002 + 2.5999999999999996 + 0.028074794716380073 + 2 + + + 0.5998135308854968 + 0.012808889207829802 + 0.15925000000000003 + 3.3999999999999995 + 0.04887565083599265 + 3 + + + 0.9592653457728847 + 0.032562034544367846 + 0.13650000000000004 + 4.199999999999999 + 0.0721159314450135 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.3965749985491234 + 0.08363779698688742 + 0.2275 + 5.0 + 0.13545939219594733 + 5 + + + + 0.11999918083878813 + 0.0003386471594997917 + 0.2275 + 1.7999999999999998 + 0.011610805045366913 + 1 + + + 0.3199704080093647 + 0.0036185223140926177 + 0.2275 + 2.5999999999999996 + 0.030962146787645105 + 2 + + + 0.5997659396443353 + 0.0141719727732467 + 0.2275 + 3.3999999999999995 + 0.05805402522683457 + 3 + + + 0.9589524795371686 + 0.03817802910819613 + 0.2275 + 4.199999999999999 + 0.09288644036293531 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.394848922468 + 0.10067426514618405 + 0.3412500000000002 + 5.0 + 0.1761088181235461 + 5 + + + + 0.11999918083878813 + 0.0003386471594997917 + 0.25025000000000003 + 1.7999999999999998 + 0.011962367794215811 + 1 + + + 0.31996713630375306 + 0.0037885205694093297 + 0.2730000000000001 + 2.5999999999999996 + 0.033886985229981056 + 2 + + + 0.5997117310865264 + 0.015554958017901886 + 0.2957500000000001 + 3.3999999999999995 + 0.06742399893807596 + 3 + + + 0.9585722542475521 + 0.0439096519890947 + 0.31850000000000017 + 4.199999999999999 + 0.1142572736532882 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.6217924755318123 + 0.0893732000974614 + 0.11375000000000005 + 5.997113636363636 + 0.11100978110460258 + 5 + + + + 0.124999122327273 + 0.0003628362423212054 + 0.20475000000000002 + 2.0 + 0.011719892959545553 + 1 + + + 0.3499662484078845 + 0.0040844799709307215 + 0.18200000000000002 + 3.0 + 0.030629127227050516 + 2 + + + 0.6747403392743871 + 0.016055098920284935 + 0.15925000000000003 + 4.0 + 0.054768598575999534 + 3 + + + 1.0989174889809106 + 0.04233503939865692 + 0.13650000000000004 + 5.0 + 0.08220166038249775 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.6196818181616361 + 0.112290855983723 + 0.2275 + 5.997113636363636 + 0.15722965165601033 + 5 + + + + 0.124999122327273 + 0.0003628362423212054 + 0.2275 + 2.0 + 0.01209458858892387 + 1 + + + 0.34996218812035595 + 0.004293333096607917 + 0.2275 + 3.0 + 0.03386484804898684 + 2 + + + 0.6746714334817476 + 0.017834999350422 + 0.2275 + 4.0 + 0.06531077838018891 + 3 + + + 1.0984391534436677 + 0.04991409994427484 + 0.2275 + 5.0 + 0.10643237958253007 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 1.0 + 0.0 + 0 + + + 1.61692916457865 + 0.135787938853464 + 0.3412500000000002 + 5.997113636363636 + 0.20517033822943906 + 5 + + + + 0.124999122327273 + 0.0003628362423212054 + 0.25025000000000003 + 2.0 + 0.012471262962690546 + 1 + + + 0.3499578400253525 + 0.00450394524910516 + 0.2730000000000001 + 3.0 + 0.037142807181081414 + 2 + + + 0.6745926808021041 + 0.01964107105559868 + 0.2957500000000001 + 4.0 + 0.07607429039707422 + 3 + + + 1.0978552538951645 + 0.057649064924254485 + 0.31850000000000017 + 5.0 + 0.13136719368262137 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.27494287417199864 + 0.004627197622346927 + 0.2274999999999998 + 1.3877787807814457e-16 + 0.036482987104108675 + 5 + + + + 0.09499876074680888 + 0.00033396294922185995 + 0.31849999999999995 + 0.8 + 0.013860829706318686 + 1 + + + 0.16998835053650707 + 0.0015663933186027689 + 0.2957499999999999 + 0.6000000000000001 + 0.024012473244855122 + 2 + + + 0.22497001935726033 + 0.0029824258478654804 + 0.27299999999999985 + 0.40000000000000013 + 0.03088677183159333 + 3 + + + 0.2599522006169254 + 0.0040983788416870115 + 0.2502499999999998 + 0.20000000000000015 + 0.03490579931772752 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.274934663223588 + 0.004897516414985326 + 0.34125 + 1.3877787807814457e-16 + 0.0408180684901866 + 5 + + + + 0.09499876074680888 + 0.00033396294922185995 + 0.34125 + 0.8 + 0.014100787296609914 + 1 + + + 0.1699877578059133 + 0.0015992574493774443 + 0.34125 + 0.6000000000000001 + 0.02523298779393353 + 2 + + + 0.22496719293200335 + 0.003098204457806738 + 0.34125 + 0.40000000000000013 + 0.03339660149197085 + 3 + + + 0.2599461235297564 + 0.004311369940023503 + 0.34125 + 0.20000000000000015 + 0.038591628390721874 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.27492554790284024 + 0.005175031139846794 + 0.45500000000000024 + 1.3877787807814457e-16 + 0.045332302899563304 + 5 + + + + 0.09499876074680888 + 0.00033396294922185995 + 0.36400000000000005 + 0.8 + 0.014342691578147927 + 1 + + + 0.16998713975741706 + 0.0016325094944158259 + 0.3867500000000001 + 0.6000000000000001 + 0.02647601076452135 + 2 + + + 0.22496415866392833 + 0.0032161244113176808 + 0.40950000000000014 + 0.40000000000000013 + 0.035976840372327006 + 3 + + + 0.25993945416830627 + 0.004529423914293125 + 0.4322500000000002 + 0.20000000000000015 + 0.04241107916031885 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.4996875198184685 + 0.015114402861786726 + 0.2274999999999998 + 1.0 + 0.06244636926262044 + 5 + + + + 0.09999862305200986 + 0.0003710699435798444 + 0.31849999999999995 + 1.0 + 0.014576314451663457 + 1 + + + 0.1999817914800034 + 0.002173107983456401 + 0.2957499999999999 + 1.0 + 0.028094334262348218 + 2 + + + 0.29993237377223403 + 0.005300367466676097 + 0.27299999999999985 + 1.0 + 0.04056952396907287 + 3 + + + 0.39983737034442135 + 0.009648479142031431 + 0.2502499999999998 + 1.0 + 0.05201595448834101 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.49960766491498043 + 0.016691404040159886 + 0.34125 + 1.0 + 0.07421466998215746 + 5 + + + + 0.09999862305200986 + 0.0003710699435798444 + 0.34125 + 1.0 + 0.014842933996431489 + 1 + + + 0.19998072325900984 + 0.002226317473802133 + 0.34125 + 1.0 + 0.029685867992862977 + 2 + + + 0.2999242736999946 + 0.00556533386359763 + 0.34125 + 1.0 + 0.04452880198929447 + 3 + + + 0.39980725594680544 + 0.010387383498790382 + 0.34125 + 1.0 + 0.05937173598572597 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.49951409083789766 + 0.018326276233791586 + 0.45500000000000024 + 1.0 + 0.08660278145478972 + 5 + + + + 0.09999862305200986 + 0.0003710699435798444 + 0.36400000000000005 + 1.0 + 0.015111716531473723 + 1 + + + 0.19997960555870725 + 0.0022801750769345353 + 0.3867500000000001 + 1.0 + 0.031307702239084016 + 2 + + + 0.29991547114559347 + 0.0058356914256571975 + 0.40950000000000014 + 1.0 + 0.04860724988752372 + 3 + + + 0.3997732722950284 + 0.011147365764104985 + 0.4322500000000002 + 1.0 + 0.06703134623615399 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.7241126138710074 + 0.03096145525450259 + 0.2274999999999998 + 2.000000000000001 + 0.08840975142113225 + 5 + + + + 0.10499848535721085 + 0.00040817693793782886 + 0.31849999999999995 + 1.2000000000000002 + 0.01529179919700823 + 1 + + + 0.22997343102494322 + 0.002856917551043549 + 0.2957499999999999 + 1.4000000000000004 + 0.03217619527984132 + 2 + + + 0.3748738925946611 + 0.008189749035634407 + 0.27299999999999985 + 1.6000000000000005 + 0.05025227610655241 + 3 + + + 0.5396219099549691 + 0.01727241574922794 + 0.2502499999999998 + 1.8000000000000007 + 0.06912610965895452 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.7238349251768894 + 0.03492601723339907 + 0.34125 + 2.000000000000001 + 0.10761127147412833 + 5 + + + + 0.10499848535721085 + 0.00040817693793782886 + 0.34125 + 1.2000000000000002 + 0.015585080696253063 + 1 + + + 0.22997170609466122 + 0.0029349894629733587 + 0.34125 + 1.4000000000000004 + 0.034138748191792426 + 2 + + + 0.3748565759142245 + 0.008662794284433015 + 0.34125 + 1.6000000000000005 + 0.055661002486618094 + 3 + + + 0.5395389121870038 + 0.018849517515183385 + 0.34125 + 1.8000000000000007 + 0.08015184358073006 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.7235023283142985 + 0.039046532305833395 + 0.45500000000000024 + 2.000000000000001 + 0.1278732600100162 + 5 + + + + 0.10499848535721085 + 0.00040817693793782886 + 0.36400000000000005 + 1.2000000000000002 + 0.015880741484799524 + 1 + + + 0.22996989635714288 + 0.0030140321014021625 + 0.3867500000000001 + 1.4000000000000004 + 0.03613939371364669 + 2 + + + 0.3748376109035082 + 0.009145915205358925 + 0.40950000000000014 + 1.6000000000000005 + 0.061237659402720454 + 3 + + + 0.539443905842568 + 0.02047444525031425 + 0.4322500000000002 + 1.8000000000000007 + 0.09165161331198915 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.948090409181951 + 0.05215922690266274 + 0.2274999999999998 + 3.0000000000000004 + 0.11437313357964397 + 5 + + + + 0.10999834766241184 + 0.0004452839322958133 + 0.31849999999999995 + 1.4 + 0.016007283942353 + 1 + + + 0.25996305664611985 + 0.003617816804428309 + 0.2957499999999999 + 1.7999999999999998 + 0.036258056297334404 + 2 + + + 0.4497900718020907 + 0.011650388489734619 + 0.27299999999999985 + 2.1999999999999997 + 0.05993502824403192 + 3 + + + 0.6792746467636039 + 0.026968441328849475 + 0.2502499999999998 + 2.6 + 0.08623626482956798 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.9474267392996354 + 0.05958535605751762 + 0.34125 + 3.0000000000000004 + 0.14100787296609912 + 5 + + + + 0.10999834766241184 + 0.0004452839322958133 + 0.34125 + 1.4 + 0.016327227396074638 + 1 + + + 0.2599604668010896 + 0.003725267294320241 + 0.34125 + 1.7999999999999998 + 0.03859162839072187 + 2 + + + 0.4497585448217688 + 0.01239034225261463 + 0.34125 + 2.1999999999999997 + 0.06679320298394169 + 3 + + + 0.6790989610344964 + 0.029695102732435023 + 0.34125 + 2.6 + 0.1009319511757341 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 0.9466223099991687 + 0.06730955119618806 + 0.45500000000000024 + 3.0000000000000004 + 0.16914373856524256 + 5 + + + + 0.10999834766241184 + 0.0004452839322958133 + 0.36400000000000005 + 1.4 + 0.016649766438125317 + 1 + + + 0.2599577436010506 + 0.0038340734263296577 + 0.3867500000000001 + 1.7999999999999998 + 0.04097108518820935 + 2 + + + 0.4497238289459463 + 0.013146476295397452 + 0.40950000000000014 + 2.1999999999999997 + 0.07386806891791715 + 3 + + + 0.6788960883758475 + 0.032506740439058296 + 0.4322500000000002 + 2.6 + 0.11627188038782425 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.1714934093204163 + 0.07869557359843685 + 0.2274999999999998 + 3.999999999999999 + 0.14033651573815573 + 5 + + + + 0.11499820996761283 + 0.0004823909266537977 + 0.31849999999999995 + 1.6 + 0.016722768687697773 + 1 + + + 0.2899504558327844 + 0.004455799961657724 + 0.2957499999999999 + 2.2 + 0.04033991731482751 + 2 + + + 0.5246764089221008 + 0.015682068666479074 + 0.27299999999999985 + 2.8 + 0.06961778038151147 + 3 + + + 0.8187644375345212 + 0.03873434391678064 + 0.2502499999999998 + 3.3999999999999995 + 0.10334642000018146 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.1701939564405834 + 0.09064783612841218 + 0.34125 + 3.999999999999999 + 0.17440447445806997 + 5 + + + + 0.11499820996761283 + 0.0004823909266537977 + 0.34125 + 1.6 + 0.017069374095896213 + 1 + + + 0.28994676588460305 + 0.004597144166969696 + 0.34125 + 2.2 + 0.043044508589651316 + 2 + + + 0.524624628003211 + 0.016747685738969006 + 0.34125 + 2.8 + 0.07792540348126531 + 3 + + + 0.8184453248089928 + 0.0429207277179035 + 0.34125 + 3.3999999999999995 + 0.1217120587707382 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.1686071937292442 + 0.1030795450246376 + 0.45500000000000024 + 3.999999999999999 + 0.21041421712046898 + 5 + + + + 0.11499820996761283 + 0.0004823909266537977 + 0.36400000000000005 + 1.6 + 0.01741879139145112 + 1 + + + 0.2899428787611766 + 0.004740291102403921 + 0.3867500000000001 + 2.2 + 0.04580277666277202 + 2 + + + 0.5245673796958771 + 0.01783698963404914 + 0.40950000000000014 + 2.8 + 0.08649847843311388 + 3 + + + 0.8180746452774897 + 0.04723919933178586 + 0.4322500000000002 + 3.3999999999999995 + 0.1408921474636594 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.3941944393224999 + 0.11055534152422725 + 0.2274999999999998 + 5.0 + 0.1662998978966675 + 5 + + + + 0.11999807227281381 + 0.0005194979210117822 + 0.31849999999999995 + 1.7999999999999998 + 0.01743825343304254 + 1 + + + 0.31993541609009923 + 0.00537086067580035 + 0.2957499999999999 + 2.5999999999999996 + 0.0444217783323206 + 2 + + + 0.5995284033025348 + 0.02028453731878834 + 0.27299999999999985 + 3.3999999999999995 + 0.079300532518991 + 3 + + + 0.9580601753549671 + 0.05256744740447425 + 0.2502499999999998 + 4.199999999999999 + 0.12045657517079496 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.391948143521908 + 0.1280863072771929 + 0.34125 + 5.0 + 0.20780107595004077 + 5 + + + + 0.11999807227281381 + 0.0005194979210117822 + 0.34125 + 1.7999999999999998 + 0.017811520795717784 + 1 + + + 0.31993036387145257 + 0.005550612601797832 + 0.34125 + 2.5999999999999996 + 0.04749738878858076 + 2 + + + 0.5994492757924406 + 0.021734484174720896 + 0.34125 + 3.3999999999999995 + 0.08905760397858892 + 3 + + + 0.9575359923713391 + 0.058522239913026186 + 0.34125 + 4.199999999999999 + 0.14249216636574225 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.389191584888808 + 0.14631123171503393 + 0.45500000000000024 + 5.0 + 0.25168469567569535 + 5 + + + + 0.11999807227281381 + 0.0005194979210117822 + 0.36400000000000005 + 1.7999999999999998 + 0.018187816344776914 + 1 + + + 0.3199250333330343 + 0.005732676372555449 + 0.3867500000000001 + 2.5999999999999996 + 0.05063446813733467 + 2 + + + 0.5993615216219151 + 0.02321700458857299 + 0.40950000000000014 + 3.3999999999999995 + 0.09912888794831057 + 3 + + + 0.9569245167680358 + 0.06466564196673193 + 0.4322500000000002 + 4.199999999999999 + 0.1655124145394945 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.6160667162661149 + 0.14772037560376716 + 0.2274999999999998 + 5.997113636363636 + 0.19226328005517926 + 5 + + + + 0.1249979345780148 + 0.0005566049153697666 + 0.31849999999999995 + 2.0 + 0.018153738178387314 + 1 + + + 0.3499177249405913 + 0.006362992034988478 + 0.2957499999999999 + 3.0 + 0.04850363934981369 + 2 + + + 0.6743415563816346 + 0.025457507129968027 + 0.27299999999999985 + 4.0 + 0.08898328465647054 + 3 + + + 1.0971307965012833 + 0.06846461212522303 + 0.2502499999999998 + 5.0 + 0.13756673034140846 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 1.0 + 0.0 + 0 + + + 1.6125017485127728 + 0.17186807700493467 + 0.34125 + 5.997113636363636 + 0.24119767744201168 + 5 + + + + 0.1249979345780148 + 0.0005566049153697666 + 0.34125 + 2.0 + 0.01855366749553936 + 1 + + + 0.3499110213096898 + 0.006585664441486299 + 0.34125 + 3.0 + 0.051950268987510206 + 2 + + + 0.6742269416962543 + 0.02735034847695323 + 0.34125 + 4.0 + 0.10018980447591254 + 3 + + + 1.096329032108888 + 0.07649474690981667 + 0.34125 + 5.0 + 0.16327227396074637 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.2748885006215875 + 0.0064499582554591595 + 0.3412499999999998 + 1.3877787807814457e-16 + 0.051494093050341055 + 5 + + + + 0.09499764826888388 + 0.00046005463785479405 + 0.43224999999999997 + 0.8 + 0.019161184235458935 + 1 + + + 0.1699776676903916 + 0.0021669258056673784 + 0.4094999999999999 + 0.6000000000000001 + 0.03342162423472776 + 2 + + + 0.22494203672793603 + 0.004140735409549656 + 0.38674999999999987 + 0.40000000000000013 + 0.043258178441435174 + 3 + + + 0.259906999560769 + 0.005705311224722029 + 0.3639999999999998 + 0.20000000000000015 + 0.049132809714922815 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.2748760187517191 + 0.00674588168206573 + 0.455 + 1.3877787807814457e-16 + 0.0562298797231306 + 5 + + + + 0.09499764826888388 + 0.00046005463785479405 + 0.455 + 0.8 + 0.019424867540717837 + 1 + + + 0.16997676841169765 + 0.002203009358072588 + 0.455 + 0.6000000000000001 + 0.03476028928338982 + 2 + + + 0.22493774452535492 + 0.0042676845633496125 + 0.455 + 0.40000000000000013 + 0.04600626522801594 + 3 + + + 0.25989776457787817 + 0.0059386067231423515 + 0.455 + 0.20000000000000015 + 0.0531627953745962 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.27486222825492734 + 0.007052708643906951 + 0.5687500000000002 + 1.3877787807814457e-16 + 0.06123743468656917 + 5 + + + + 0.09499764826888388 + 0.00046005463785479405 + 0.47775 + 0.8 + 0.019691502229035956 + 1 + + + 0.16997583204867478 + 0.0022396808960410248 + 0.5005000000000001 + 0.6000000000000001 + 0.03613308228925047 + 2 + + + 0.22493315102721556 + 0.004397878896589579 + 0.5232500000000001 + 0.40000000000000013 + 0.04886112391707385 + 3 + + + 0.2598876727206231 + 0.006179574001598174 + 0.5460000000000002 + 0.20000000000000015 + 0.05739544819073159 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.4993773412318522 + 0.021263293717336276 + 0.3412499999999998 + 1.0 + 0.08940492895168857 + 5 + + + + 0.09999738696542654 + 0.00051117181983866 + 0.43224999999999997 + 1.0 + 0.02015424753994163 + 1 + + + 0.19996504048393232 + 0.003008348052573344 + 0.4094999999999999 + 1.0 + 0.039149047228352996 + 2 + + + 0.299868613290485 + 0.007375323569294989 + 0.38674999999999987 + 1.0 + 0.05700813587496229 + 3 + + + 0.399680108007437 + 0.013497778099472928 + 0.3639999999999998 + 1.0 + 0.07375338750796841 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.4992556275649306 + 0.02298510568475771 + 0.455 + 1.0 + 0.10223614495114651 + 5 + + + + 0.09999738696542654 + 0.00051117181983866 + 0.455 + 1.0 + 0.020447228990229303 + 1 + + + 0.19996341942776882 + 0.0030667637826887247 + 0.455 + 1.0 + 0.040894457980458605 + 2 + + + 0.29985630412728825 + 0.0076657074604445825 + 0.455 + 1.0 + 0.061341686970687904 + 3 + + + 0.39963427838546844 + 0.014306080151535377 + 0.455 + 1.0 + 0.08178891596091721 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.49911437507038686 + 0.024794467342184892 + 0.5687500000000002 + 1.0 + 0.1160077906844933 + 5 + + + + 0.09999738696542654 + 0.00051117181983866 + 0.47775 + 1.0 + 0.020743489755027215 + 1 + + + 0.1999617264746433 + 0.003126161830593523 + 0.5005000000000001 + 1.0 + 0.042685811456815055 + 2 + + + 0.29984298710153273 + 0.007964259030218579 + 0.5232500000000001 + 1.0 + 0.0658559563902135 + 3 + + + 0.3995829240993689 + 0.015146295766537041 + 0.5460000000000002 + 1.0 + 0.09028529972040046 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.7232137588062229 + 0.04375615159433309 + 0.3412499999999998 + 2.000000000000001 + 0.12731576485303614 + 5 + + + + 0.1049971256619692 + 0.0005622890018225261 + 0.43224999999999997 + 1.2000000000000002 + 0.021147310844424328 + 1 + + + 0.22994892647915666 + 0.003957211514925825 + 0.4094999999999999 + 1.4000000000000004 + 0.04487647022197823 + 2 + + + 0.3747541798932885 + 0.011413220552886256 + 0.38674999999999987 + 1.6000000000000005 + 0.07075809330848942 + 3 + + + 0.5392516112072407 + 0.024232512897223904 + 0.3639999999999998 + 1.8000000000000007 + 0.09837396530101404 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.7227900163014723 + 0.048077192777598685 + 0.455 + 2.000000000000001 + 0.14824241017916248 + 5 + + + + 0.1049971256619692 + 0.0005622890018225261 + 0.455 + 1.2000000000000002 + 0.02146959043974077 + 1 + + + 0.22994630834985658 + 0.004042914777744001 + 0.455 + 1.4000000000000004 + 0.0470286266775274 + 2 + + + 0.3747278525497831 + 0.011931447153769622 + 0.455 + 1.6000000000000005 + 0.07667710871335989 + 3 + + + 0.5391251994749467 + 0.02595616962718824 + 0.455 + 1.8000000000000007 + 0.11041503654723826 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.7222887554776465 + 0.0526335428495118 + 0.5687500000000002 + 2.000000000000001 + 0.1707781466824175 + 5 + + + + 0.1049971256619692 + 0.0005622890018225261 + 0.47775 + 1.2000000000000002 + 0.021795477281018473 + 1 + + + 0.22994356773655603 + 0.004130089218393031 + 0.5005000000000001 + 1.4000000000000004 + 0.049238540624379656 + 2 + + + 0.37469917610433584 + 0.012464932424902308 + 0.5232500000000001 + 1.6000000000000005 + 0.08285078886335319 + 3 + + + 0.538981771249667 + 0.027752153828343264 + 0.5460000000000002 + 1.8000000000000007 + 0.12317515125006939 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.9461334866433975 + 0.07390150388088951 + 0.3412499999999998 + 3.0000000000000004 + 0.16522660075438364 + 5 + + + + 0.10999686435851184 + 0.000613406183806392 + 0.43224999999999997 + 1.4 + 0.022140374148907023 + 1 + + + 0.25992891232161686 + 0.005013502094775926 + 0.4094999999999999 + 1.7999999999999998 + 0.05060389321560345 + 2 + + + 0.44958980485916045 + 0.01625392016451004 + 0.38674999999999987 + 2.1999999999999997 + 0.08450805074201652 + 3 + + + 0.6785584157992838 + 0.037904508086898166 + 0.3639999999999998 + 2.6 + 0.1229945430940596 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.9451203633060933 + 0.08198036391530111 + 0.455 + 3.0000000000000004 + 0.19424867540717836 + 5 + + + + 0.10999686435851184 + 0.000613406183806392 + 0.455 + 1.4 + 0.02249195188925223 + 1 + + + 0.2599249807878525 + 0.005131446338982201 + 0.455 + 1.7999999999999998 + 0.053162795374596186 + 2 + + + 0.4495418576702852 + 0.01706426735043855 + 0.455 + 2.1999999999999997 + 0.09201253045603186 + 3 + + + 0.6782907218500915 + 0.040881901525171266 + 0.455 + 2.6 + 0.13904115713355925 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 0.9439096551318024 + 0.09050730298341036 + 0.5687500000000002 + 3.0000000000000004 + 0.22554850268034157 + 5 + + + + 0.10999686435851184 + 0.000613406183806392 + 0.47775 + 1.4 + 0.022847464807009728 + 1 + + + 0.2599208575736147 + 0.005251444943421298 + 0.5005000000000001 + 1.7999999999999998 + 0.05579126979194423 + 2 + + + 0.4494893871287453 + 0.0178991062669263 + 0.5232500000000001 + 2.1999999999999997 + 0.09984562133649282 + 3 + + + 0.6779846951738916 + 0.04398760987380776 + 0.5460000000000002 + 2.6 + 0.15606500277973823 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.1678733356207465 + 0.11166329443978551 + 0.3412499999999998 + 3.999999999999999 + 0.20313743665573114 + 5 + + + + 0.11499660305505449 + 0.0006645233657902581 + 0.43224999999999997 + 1.6 + 0.02313343745338972 + 1 + + + 0.28990458471140806 + 0.006177204160265624 + 0.4094999999999999 + 2.2 + 0.05633131620922868 + 2 + + + 0.5243665626002599 + 0.021896817949915336 + 0.38674999999999987 + 2.8 + 0.09825800817554364 + 3 + + + 0.8175375492213028 + 0.054507412618666554 + 0.3639999999999998 + 3.3999999999999995 + 0.1476151208871052 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.1658898383928396 + 0.12463830707464324 + 0.455 + 3.999999999999999 + 0.24025494063519431 + 5 + + + + 0.11499660305505449 + 0.0006645233657902581 + 0.455 + 1.6 + 0.0235143133387637 + 1 + + + 0.2898989824167737 + 0.006332340689472854 + 0.455 + 2.2 + 0.05929696407166499 + 2 + + + 0.5242877957669156 + 0.0230634049392427 + 0.455 + 2.8 + 0.10734795219870386 + 3 + + + 0.8170512321540927 + 0.05907436660819709 + 0.455 + 3.3999999999999995 + 0.1676672777198803 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.1635048734397109 + 0.13833060288997923 + 0.5687500000000002 + 3.999999999999999 + 0.28031885867826567 + 5 + + + + 0.11499660305505449 + 0.0006645233657902581 + 0.47775 + 1.6 + 0.023899452333000983 + 1 + + + 0.28989309780244576 + 0.006490208849030307 + 0.5005000000000001 + 2.2 + 0.062343998959508824 + 2 + + + 0.5242013007035338 + 0.024265825924197217 + 0.5232500000000001 + 2.8 + 0.11684045380963248 + 3 + + + 0.8164924758135903 + 0.06384039998348433 + 0.5460000000000002 + 3.3999999999999995 + 0.18895485430940712 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.388171500846281 + 0.1569964808093332 + 0.3412499999999998 + 5.0 + 0.2410482725570787 + 5 + + + + 0.11999634175159715 + 0.0007156405477741239 + 0.43224999999999997 + 1.7999999999999998 + 0.02412650075787242 + 1 + + + 0.31987553040867417 + 0.007448300545830888 + 0.4094999999999999 + 2.5999999999999996 + 0.062058739202853916 + 2 + + + 0.5990755346863574 + 0.028341211268073953 + 0.38674999999999987 + 3.3999999999999995 + 0.11200796560907075 + 3 + + + 0.9561261881210428 + 0.07403353477325017 + 0.3639999999999998 + 4.199999999999999 + 0.17223569868015082 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.3847441895819936 + 0.17598026964595723 + 0.455 + 5.0 + 0.28626120586321024 + 5 + + + + 0.11999634175159715 + 0.0007156405477741239 + 0.455 + 1.7999999999999998 + 0.024536674788275162 + 1 + + + 0.3198678589834487 + 0.007645578279866207 + 0.455 + 2.5999999999999996 + 0.06543113276873377 + 2 + + + 0.5989551530284373 + 0.029927970099121112 + 0.455 + 3.3999999999999995 + 0.12268337394137581 + 3 + + + 0.9553273563673934 + 0.08052272523016665 + 0.455 + 4.199999999999999 + 0.1962933983062013 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.3806067875242114 + 0.1959959768610331 + 0.5687500000000002 + 5.0 + 0.3350892146761898 + 5 + + + + 0.11999634175159715 + 0.0007156405477741239 + 0.47775 + 1.7999999999999998 + 0.024951439858992237 + 1 + + + 0.31985979032517675 + 0.007846358738260452 + 0.5005000000000001 + 2.5999999999999996 + 0.0688967281270734 + 2 + + + 0.5988226108938135 + 0.031563975107505284 + 0.5232500000000001 + 3.3999999999999995 + 0.13383528628277214 + 3 + + + 0.954406266395015 + 0.08729554379152146 + 0.5460000000000002 + 4.199999999999999 + 0.22184470583907598 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 1.0 + 0.0 + 0 + + + 1.606767866722187 + 0.20984708637548413 + 0.3412499999999998 + 5.997113636363636 + 0.27895910845842625 + 5 + + + + 0.12499608044813981 + 0.00076675772975799 + 0.43224999999999997 + 2.0 + 0.025119564062355118 + 1 + + + 0.34984133623911406 + 0.008826772552424055 + 0.4094999999999999 + 3.0 + 0.06778616219647914 + 2 + + + 0.6737078109122759 + 0.03558629937432013 + 0.38674999999999987 + 4.0 + 0.12575792304259786 + 3 + + + 1.094261686701656 + 0.0964738456081166 + 0.3639999999999998 + 5.0 + 0.19685627647319642 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.2748068829770464 + 0.008477878058988836 + 0.45499999999999974 + 1.3877787807814457e-16 + 0.06812789674268245 + 5 + + + + 0.09499598552205861 + 0.0006010714588902599 + 0.5459999999999999 + 0.8 + 0.025080146017587228 + 1 + + + 0.169961678058422 + 0.0028372484874491346 + 0.5232499999999999 + 0.6000000000000001 + 0.043899936621932895 + 2 + + + 0.22490009937626732 + 0.005431593235612166 + 0.5004999999999998 + 0.40000000000000013 + 0.05700329093062127 + 3 + + + 0.2598391871463208 + 0.0074940857060487465 + 0.4777499999999998 + 0.20000000000000015 + 0.06491199947876516 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.2747883815181684 + 0.008812176964884472 + 0.56875 + 1.3877787807814457e-16 + 0.07346647409617092 + 5 + + + + 0.09499598552205861 + 0.0006010714588902599 + 0.56875 + 0.8 + 0.025379327415040856 + 1 + + + 0.1699603440471038 + 0.00287814955155151 + 0.56875 + 0.6000000000000001 + 0.04541563853217838 + 2 + + + 0.22489373437078436 + 0.005575269006162885 + 0.56875 + 0.40000000000000013 + 0.06010893335141256 + 3 + + + 0.25982549619513273 + 0.007757802286648092 + 0.56875 + 0.20000000000000015 + 0.06945921187274341 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.2747678603033008 + 0.009162653518715013 + 0.6825000000000002 + 1.3877787807814457e-16 + 0.07920896349582235 + 5 + + + + 0.09499598552205861 + 0.0006010714588902599 + 0.5915 + 0.8 + 0.025682891547961873 + 1 + + + 0.16995895222458773 + 0.0029199234672891167 + 0.6142500000000001 + 0.6000000000000001 + 0.04698202607961807 + 2 + + + 0.22488690367271913 + 0.005723760870192718 + 0.6370000000000001 + 0.40000000000000013 + 0.06337318359903374 + 3 + + + 0.2598104829732665 + 0.008032902270627622 + 0.6597500000000002 + 0.20000000000000015 + 0.07430756475947524 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.4989101553023475 + 0.028075482208581005 + 0.45499999999999974 + 1.0 + 0.11914171693413693 + 5 + + + + 0.09999553946895401 + 0.0006678571765447333 + 0.5459999999999999 + 1.0 + 0.026382657714568214 + 1 + + + 0.1999399629997038 + 0.003940341287339298 + 0.5232499999999999 + 1.0 + 0.051454162293021605 + 2 + + + 0.29977298720144596 + 0.009685248836509515 + 0.5004999999999998 + 1.0 + 0.07524982836119505 + 3 + + + 0.39944377466850295 + 0.017772741317271745 + 0.4777499999999998 + 1.0 + 0.0978022929845942 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.49872974629610584 + 0.03001426981523258 + 0.56875 + 1.0 + 0.13357540744758342 + 5 + + + + 0.09999553946895401 + 0.0006678571765447333 + 0.56875 + 1.0 + 0.026715081489516693 + 1 + + + 0.1999375581361885 + 0.004006547280995004 + 0.56875 + 1.0 + 0.053430162979033385 + 2 + + + 0.29975473206694125 + 0.010013687646696922 + 0.56875 + 1.0 + 0.08014524446855006 + 3 + + + 0.3993758264222875 + 0.01868499125910681 + 0.56875 + 1.0 + 0.10686032595806674 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.49851959013792824 + 0.03208264734951771 + 0.6825000000000002 + 1.0 + 0.14940724559719726 + 5 + + + + 0.09999553946895401 + 0.0006678571765447333 + 0.5915 + 1.0 + 0.02705237497054004 + 1 + + + 0.1999350419303158 + 0.004074211355691603 + 0.6142500000000001 + 1.0 + 0.05547439652235575 + 2 + + + 0.29973493273436114 + 0.01035424221757986 + 0.6370000000000001 + 1.0 + 0.08530912216447677 + 3 + + + 0.3992994484045314 + 0.019644537256398104 + 0.6597500000000002 + 1.0 + 0.11660320703246328 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.7218579736799652 + 0.057890700268436464 + 0.45499999999999974 + 2.000000000000001 + 0.17015553712559148 + 5 + + + + 0.10499509341584941 + 0.0007346428941992066 + 0.5459999999999999 + 1.2000000000000002 + 0.027685169411549203 + 1 + + + 0.22991223527951998 + 0.005184615482898154 + 0.5232499999999999 + 1.4000000000000004 + 0.059008387964110315 + 2 + + + 0.374574555704977 + 0.014998771478735759 + 0.5004999999999998 + 1.6000000000000005 + 0.09349636579176886 + 3 + + + 0.5386946358494151 + 0.03194944146735339 + 0.4777499999999998 + 1.8000000000000007 + 0.13069258649042328 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.7212299861000381 + 0.06274451805946256 + 0.56875 + 2.000000000000001 + 0.19368434079899605 + 5 + + + + 0.10499509341584941 + 0.0007346428941992066 + 0.56875 + 1.2000000000000002 + 0.028050835563992526 + 1 + + + 0.2299083510297665 + 0.0052817370366597585 + 0.56875 + 1.4000000000000004 + 0.06144468742588839 + 2 + + + 0.37453550850889616 + 0.015584619698065454 + 0.56875 + 1.6000000000000005 + 0.1001815555856876 + 3 + + + 0.5385072136752477 + 0.03389237816008651 + 0.56875 + 1.8000000000000007 + 0.14426144004339014 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.7204849286797178 + 0.06794525029794007 + 0.6825000000000002 + 2.000000000000001 + 0.21960552769857222 + 5 + + + + 0.10499509341584941 + 0.0007346428941992066 + 0.5915 + 1.2000000000000002 + 0.028421858393118213 + 1 + + + 0.22990427806022357 + 0.005381042050548655 + 0.6142500000000001 + 1.4000000000000004 + 0.06396676696509343 + 2 + + + 0.3744928829503823 + 0.016193088773699127 + 0.6370000000000001 + 1.6000000000000005 + 0.10724506072991981 + 3 + + + 0.5382940022191202 + 0.03594231626497791 + 0.6597500000000002 + 1.8000000000000007 + 0.15889884930545137 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.9431802283247454 + 0.09785935103261857 + 0.45499999999999974 + 3.0000000000000004 + 0.2211693573170459 + 5 + + + + 0.10999464736274481 + 0.0008014286118536798 + 0.5459999999999999 + 1.4 + 0.02898768110853019 + 1 + + + 0.25987778047890386 + 0.006570039091988922 + 0.5232499999999999 + 1.7999999999999998 + 0.06656261363519901 + 2 + + + 0.44928922170615837 + 0.02137099613925258 + 0.5004999999999998 + 2.1999999999999997 + 0.11174290322234261 + 3 + + + 0.677480631177308 + 0.05001248514288045 + 0.4777499999999998 + 2.6 + 0.1635828799962523 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.9416795899490947 + 0.10690990280879695 + 0.56875 + 3.0000000000000004 + 0.25379327415040853 + 5 + + + + 0.10999464736274481 + 0.0008014286118536798 + 0.56875 + 1.4 + 0.02938658963846836 + 1 + + + 0.25987194740519587 + 0.0067036831292328035 + 0.56875 + 1.7999999999999998 + 0.0694592118727434 + 2 + + + 0.4492181083318288 + 0.022286646653991056 + 0.56875 + 2.1999999999999997 + 0.12021786670282511 + 3 + + + 0.6770837999274408 + 0.05336442437656587 + 0.56875 + 2.6 + 0.1816625541287135 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 0.9398822530493937 + 0.11661736966311678 + 0.6825000000000002 + 3.0000000000000004 + 0.289803809799947 + 5 + + + + 0.10999464736274481 + 0.0008014286118536798 + 0.5915 + 1.4 + 0.02979134181569638 + 1 + + + 0.2598658201902012 + 0.006840375775484771 + 0.6142500000000001 + 1.7999999999999998 + 0.0724591374078311 + 2 + + + 0.44914013307880557 + 0.02323857974715831 + 0.6370000000000001 + 2.1999999999999997 + 0.1291809992953628 + 3 + + + 0.6766291426292728 + 0.05690575897781151 + 0.6597500000000002 + 2.6 + 0.20119449157843933 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.1624102415859066 + 0.14789576068355675 + 0.45499999999999974 + 3.999999999999999 + 0.27218317750850035 + 5 + + + + 0.11499420130964022 + 0.0008682143295081533 + 0.5459999999999999 + 1.6 + 0.03029019280551118 + 1 + + + 0.2898358843416613 + 0.008096576645215747 + 0.5232499999999999 + 2.2 + 0.07411683930628774 + 2 + + + 0.5239014205744237 + 0.028800531008835333 + 0.5004999999999998 + 2.8 + 0.1299894406529164 + 3 + + + 0.8156909971667619 + 0.0719470225546968 + 0.4777499999999998 + 3.3999999999999995 + 0.19647317350208132 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.159474836197512 + 0.16238521182150253 + 0.56875 + 3.999999999999999 + 0.3139022075018211 + 5 + + + + 0.11499420130964022 + 0.0008682143295081533 + 0.56875 + 1.6 + 0.030722343712944196 + 1 + + + 0.28982757212957894 + 0.008272345917663161 + 0.56875 + 2.2 + 0.0774737363195984 + 2 + + + 0.5237846006374535 + 0.03011806760538932 + 0.56875 + 2.8 + 0.14025417781996263 + 3 + + + 0.814970287814056 + 0.07708128961408774 + 0.56875 + 3.3999999999999995 + 0.21906366821403686 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.1559395114034894 + 0.1779185383162733 + 0.6825000000000002 + 3.999999999999999 + 0.36000209190132193 + 5 + + + + 0.11499420130964022 + 0.0008682143295081533 + 0.5915 + 1.6 + 0.031160825238274553 + 1 + + + 0.2898188281168897 + 0.008452168284421802 + 0.6142500000000001 + 2.2 + 0.08095150785056879 + 2 + + + 0.5236560939604856 + 0.031488644530927506 + 0.6370000000000001 + 2.8 + 0.15111693786080585 + 3 + + + 0.8141406939925129 + 0.08250856945982404 + 0.6597500000000002 + 3.3999999999999995 + 0.2434901338514274 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.3790857451489453 + 0.20789294139777786 + 0.45499999999999974 + 5.0 + 0.3231969976999548 + 5 + + + + 0.1199937552565356 + 0.0009350000471626263 + 0.5459999999999999 + 1.7999999999999998 + 0.03159270450249216 + 1 + + + 0.3197858327908362 + 0.009764189186721147 + 0.5232499999999999 + 2.5999999999999996 + 0.08167106497737643 + 2 + + + 0.5983956094913564 + 0.03728575778100962 + 0.5004999999999998 + 3.3999999999999995 + 0.14823597808349015 + 3 + + + 0.9532154349708131 + 0.09773506695357606 + 0.4777499999999998 + 4.199999999999999 + 0.22936346700791033 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.3740194870458526 + 0.2290133901672069 + 0.56875 + 5.0 + 0.3740111408532336 + 5 + + + + 0.1199937552565356 + 0.0009350000471626263 + 0.56875 + 1.7999999999999998 + 0.032058097787420026 + 1 + + + 0.31977445027923684 + 0.009987681810132428 + 0.56875 + 2.5999999999999996 + 0.0854882607664534 + 2 + + + 0.5982170833859748 + 0.03907689965308475 + 0.56875 + 3.3999999999999995 + 0.1602904889371001 + 3 + + + 0.9520320761041776 + 0.10501885167762731 + 0.56875 + 4.199999999999999 + 0.2564647822993602 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 1.0 + 0.0 + 0 + + + 1.36789708897081 + 0.25162158440124666 + 0.6825000000000002 + 5.0 + 0.4302003740026967 + 5 + + + + 0.1199937552565356 + 0.0009350000471626263 + 0.5915 + 1.7999999999999998 + 0.03253030866085272 + 1 + + + 0.3197624618806545 + 0.010216370862757068 + 0.6142500000000001 + 2.5999999999999996 + 0.08944387829330644 + 2 + + + 0.5980202143891449 + 0.040940863287154725 + 0.6370000000000001 + 3.3999999999999995 + 0.17305287642624884 + 3 + + + 0.9506655109108223 + 0.11271866874090168 + 0.6597500000000002 + 4.199999999999999 + 0.28578577612441536 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.27468548581104846 + 0.010811141589746108 + 0.5687499999999998 + 1.3877787807814457e-16 + 0.08718351608531681 + 5 + + + + 0.0949935089471535 + 0.0007642987782401668 + 0.65975 + 0.8 + 0.031919914773339046 + 1 + + + 0.1699378778571408 + 0.0036114266005916095 + 0.6369999999999999 + 0.6000000000000001 + 0.05597064331960054 + 2 + + + 0.22483770272650633 + 0.006919701626157898 + 0.6142499999999999 + 0.40000000000000013 + 0.07279596684915852 + 3 + + + 0.2597383153335804 + 0.009553484787550299 + 0.5914999999999998 + 0.20000000000000015 + 0.08300659377196823 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.2746578832061916 + 0.01120244239867929 + 0.6825 + 1.3877787807814457e-16 + 0.09341878691168067 + 5 + + + + 0.0949935089471535 + 0.0007642987782401668 + 0.6825 + 0.8 + 0.03227194456948968 + 1 + + + 0.16993588248239372 + 0.003659494543364724 + 0.6825 + 0.6000000000000001 + 0.05774979554540259 + 2 + + + 0.22482819335754367 + 0.007088242558781301 + 0.6825 + 0.40000000000000013 + 0.07643355292773872 + 3 + + + 0.25971787958622516 + 0.009862399548768212 + 0.6825 + 0.20000000000000015 + 0.08832321671649808 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.2746269639741775 + 0.011617965494290566 + 0.7962500000000002 + 1.3877787807814457e-16 + 0.1002603626630672 + 5 + + + + 0.0949935089471535 + 0.0007642987782401668 + 0.70525 + 0.8 + 0.032630544887945284 + 1 + + + 0.16993379144877258 + 0.003708870395434831 + 0.7280000000000001 + 0.6000000000000001 + 0.05960494913751481 + 2 + + + 0.22481791851539876 + 0.00726399716699889 + 0.7507500000000001 + 0.40000000000000013 + 0.08030904192944613 + 3 + + + 0.2596952730026894 + 0.01018835997021138 + 0.7735000000000002 + 0.20000000000000015 + 0.09409171708561678 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.4982157934525988 + 0.035874150668559764 + 0.5687499999999998 + 1.0 + 0.15303493883638075 + 5 + + + + 0.09999278771905944 + 0.0008492208647112964 + 0.65975 + 1.0 + 0.03357932374993872 + 1 + + + 0.19990263960328467 + 0.005016306747687314 + 0.6369999999999999 + 1.0 + 0.06562180041620698 + 2 + + + 0.29963074997228184 + 0.012344769394995245 + 0.6142499999999999 + 1.0 + 0.09618013607523186 + 3 + + + 0.3990924074060589 + 0.022680904681050162 + 0.5914999999999998 + 1.0 + 0.125302910156747 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.49794710759949784 + 0.03813415657566251 + 0.6825 + 1.0 + 0.16985233983941941 + 5 + + + + 0.09999278771905944 + 0.0008492208647112964 + 0.6825 + 1.0 + 0.033970467967883874 + 1 + + + 0.19989904263099073 + 0.005094100295054669 + 0.6825 + 1.0 + 0.06794093593576775 + 2 + + + 0.29960348473420784 + 0.01272974020223784 + 0.6825 + 1.0 + 0.10191140390365164 + 3 + + + 0.39899106689523633 + 0.023747329960926235 + 0.6825 + 1.0 + 0.13588187187153553 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.4976301172155208 + 0.040587503338238365 + 0.7962500000000002 + 1.0 + 0.18876947543011366 + 5 + + + + 0.09999278771905944 + 0.0008492208647112964 + 0.70525 + 1.0 + 0.03436891276616788 + 1 + + + 0.19989526237210223 + 0.005174078347664224 + 0.7280000000000001 + 1.0 + 0.07036238504466791 + 2 + + + 0.29957369899354264 + 0.013132845591682794 + 0.7507500000000001 + 1.0 + 0.10804536623545823 + 3 + + + 0.39887601281081264 + 0.024884448666625238 + 0.7735000000000002 + 1.0 + 0.14748863971164933 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.7198444607284108 + 0.0740133526347723 + 0.5687499999999998 + 2.000000000000001 + 0.2188863615874448 + 5 + + + + 0.10499206649096537 + 0.000934142951182426 + 0.65975 + 1.2000000000000002 + 0.0352387327265384 + 1 + + + 0.22985763176534976 + 0.0066011511014067055 + 0.6369999999999999 + 1.4000000000000004 + 0.07527295751281342 + 2 + + + 0.37430744092615387 + 0.019122844464617005 + 0.6142499999999999 + 1.6000000000000005 + 0.11956430530130523 + 3 + + + 0.5378669367665077 + 0.040791032085727326 + 0.5914999999999998 + 1.8000000000000007 + 0.16759922654152581 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.7189102321797178 + 0.07965218330514912 + 0.6825 + 2.000000000000001 + 0.24628589276715815 + 5 + + + + 0.10499206649096537 + 0.000934142951182426 + 0.6825 + 1.2000000000000002 + 0.03566899136627807 + 1 + + + 0.2298518222430841 + 0.006715253905777523 + 0.6825 + 1.4000000000000004 + 0.07813207632613292 + 2 + + + 0.3742491336028115 + 0.019809067932286005 + 0.6825 + 1.6000000000000005 + 0.12738925487956454 + 3 + + + 0.537587562206632 + 0.04305849532564818 + 0.6825 + 1.8000000000000007 + 0.18344052702657296 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.71778728740081 + 0.08580548424472521 + 0.7962500000000002 + 2.000000000000001 + 0.2772785881971602 + 5 + + + + 0.10499206649096537 + 0.000934142951182426 + 0.70525 + 1.2000000000000002 + 0.03610728064439048 + 1 + + + 0.22984570330758203 + 0.006832627425799177 + 0.7280000000000001 + 1.4000000000000004 + 0.08111982095182103 + 2 + + + 0.37418501330507925 + 0.02052911951195716 + 0.7507500000000001 + 1.6000000000000005 + 0.13578169054147035 + 3 + + + 0.5372664766313172 + 0.045485472356659104 + 0.7735000000000002 + 1.8000000000000007 + 0.20088556233768196 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.93879843056099 + 0.12509270950402065 + 0.5687499999999998 + 3.0000000000000004 + 0.28473778433850866 + 5 + + + + 0.10999134526287131 + 0.0010190650376535556 + 0.65975 + 1.4 + 0.03689814170313808 + 1 + + + 0.25980169255857927 + 0.008365893358347237 + 0.6369999999999999 + 1.7999999999999998 + 0.08492411460941984 + 2 + + + 0.44884233246625094 + 0.027251494515728038 + 0.6142499999999999 + 2.1999999999999997 + 0.14294847452737852 + 3 + + + 0.6758797655129212 + 0.06385925715209441 + 0.5914999999999998 + 2.6 + 0.20989554292630455 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.9365689616651547 + 0.13556576443782192 + 0.6825 + 3.0000000000000004 + 0.32271944569489674 + 5 + + + + 0.10999134526287131 + 0.0010190650376535556 + 0.6825 + 1.4 + 0.03736751476467226 + 1 + + + 0.2597929684986334 + 0.008522882012247416 + 0.6825 + 1.7999999999999998 + 0.08832321671649807 + 2 + + + 0.44873616381120063 + 0.028323311139252697 + 0.6825 + 2.1999999999999997 + 0.15286710585547741 + 3 + + + 0.6752885931134505 + 0.06776399255522389 + 0.6825 + 2.6 + 0.2309991821816103 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 0.9338639693708394 + 0.14700475625268608 + 0.7962500000000002 + 3.0000000000000004 + 0.36578770096420654 + 5 + + + + 0.10999134526287131 + 0.0010190650376535556 + 0.70525 + 1.4 + 0.037845648522613067 + 1 + + + 0.25978376374176243 + 0.008684436470210286 + 0.7280000000000001 + 1.7999999999999998 + 0.09187725685897412 + 2 + + + 0.44861888707940245 + 0.029449327534525536 + 0.7507500000000001 + 2.1999999999999997 + 0.1635180148474824 + 3 + + + 0.6746042898814097 + 0.0719501002045175 + 0.7735000000000002 + 2.6 + 0.2542824849637144 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 1.1543140159017384 + 0.188930758672728 + 0.5687499999999998 + 3.999999999999999 + 0.35058920708957264 + 5 + + + + 0.11499062403477726 + 0.0011039871241246852 + 0.65975 + 1.6 + 0.03855755067973776 + 1 + + + 0.2897336606287624 + 0.010310459980129048 + 0.6369999999999999 + 2.2 + 0.0945752717060263 + 2 + + + 0.5232100310347148 + 0.03672781355653229 + 0.6142499999999999 + 2.8 + 0.16633264375345191 + 3 + + + 0.8129497710766187 + 0.0918543523357527 + 0.5914999999999998 + 3.3999999999999995 + 0.2521918593110834 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 1.1499600831050354 + 0.20561862137695358 + 0.6825 + 3.999999999999999 + 0.3991529986226355 + 5 + + + + 0.11499062403477726 + 0.0011039871241246852 + 0.6825 + 1.6 + 0.039066038163066454 + 1 + + + 0.2897212290735577 + 0.010516903131947445 + 0.6825 + 2.2 + 0.09851435710686324 + 2 + + + 0.5230356631232952 + 0.0382689759298291 + 0.6825 + 2.8 + 0.17834495683139034 + 3 + + + 0.8118768503546804 + 0.09782312097430891 + 0.6825 + 3.3999999999999995 + 0.27855783733664774 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 1.1446498589893326 + 0.22382410296666055 + 0.7962500000000002 + 3.999999999999999 + 0.454296813731253 + 5 + + + + 0.11499062403477726 + 0.0011039871241246852 + 0.70525 + 1.6 + 0.03958401640083566 + 1 + + + 0.28970809373225626 + 0.010729415215002893 + 0.7280000000000001 + 2.2 + 0.10263469276612724 + 2 + + + 0.5228424282947332 + 0.039889270735869196 + 0.7507500000000001 + 2.8 + 0.19125433915349457 + 3 + + + 0.8106291827528216 + 0.10422533532100346 + 0.7735000000000002 + 3.3999999999999995 + 0.30767940758974704 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 1.3656395539607018 + 0.2653012409334961 + 0.5687499999999998 + 5.0 + 0.41644062984063657 + 5 + + + + 0.1199899028066832 + 0.0011889092105958148 + 0.65975 + 1.7999999999999998 + 0.04021695965633743 + 1 + + + 0.3196523750958156 + 0.012434770196086194 + 0.6369999999999999 + 2.5999999999999996 + 0.10422642880263272 + 2 + + + 0.5973852013535067 + 0.047548422910708626 + 0.6142499999999999 + 3.3999999999999995 + 0.18971681297952522 + 3 + + + 0.948897085061651 + 0.12473851335619696 + 0.5914999999999998 + 4.199999999999999 + 0.2944881756958621 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 1.0 + 0.0 + 0 + + + 1.3581398370054718 + 0.28949011546398407 + 0.6825 + 5.0 + 0.47558655155037416 + 5 + + + + 0.1199899028066832 + 0.0011889092105958148 + 0.6825 + 1.7999999999999998 + 0.04076456156146065 + 1 + + + 0.31963535219061223 + 0.012697227666355618 + 0.6825 + 2.5999999999999996 + 0.10870549749722838 + 2 + + + 0.5971187946702023 + 0.04964199049787175 + 0.6825 + 3.3999999999999995 + 0.20382280780730322 + 3 + + + 0.9471368396490466 + 0.13318644793148843 + 0.6825 + 4.199999999999999 + 0.3261164924916852 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.2745017057788426 + 0.013601722966924886 + 0.6824999999999998 + 1.3877787807814457e-16 + 0.10986471929680308 + 5 + + + + 0.09498973899654928 + 0.0009609292494111888 + 0.7735 + 0.8 + 0.04014330062593861 + 1 + + + 0.1699017277473458 + 0.004541552776976524 + 0.7507499999999999 + 0.6000000000000001 + 0.07043023631091108 + 2 + + + 0.22474308619187366 + 0.008703615960287809 + 0.7279999999999999 + 0.40000000000000013 + 0.09165687460350536 + 3 + + + 0.2595855285385648 + 0.012018364641139648 + 0.7052499999999998 + 0.20000000000000015 + 0.1045684041093415 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.2744593082762997 + 0.01407917592072126 + 0.79625 + 1.3877787807814457e-16 + 0.11745583591366138 + 5 + + + + 0.09498973899654928 + 0.0009609292494111888 + 0.79625 + 0.8 + 0.04057565240653756 + 1 + + + 0.16989864985982453 + 0.004600496768712013 + 0.79625 + 0.6000000000000001 + 0.07260906220117247 + 2 + + + 0.22472844652361662 + 0.008909819542742486 + 0.79625 + 0.40000000000000013 + 0.09610022938390475 + 3 + + + 0.2595541145960626 + 0.012395641177347603 + 0.79625 + 0.20000000000000015 + 0.11104915395473439 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.2744110734400991 + 0.014594049381514375 + 0.9100000000000003 + 1.3877787807814457e-16 + 0.12598726561389223 + 5 + + + + 0.09498973899654928 + 0.0009609292494111888 + 0.8190000000000001 + 0.8 + 0.04101817468474475 + 1 + + + 0.16989540267622633 + 0.004661463726918124 + 0.8417500000000001 + 0.6000000000000001 + 0.07490556421852715 + 2 + + + 0.22471245886796523 + 0.009127173761499551 + 0.8645000000000002 + 0.40000000000000013 + 0.10091211865853952 + 3 + + + 0.25951888094863046 + 0.012799255118111088 + 0.8872500000000002 + 0.20000000000000015 + 0.11823033941621588 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.4971685283788468 + 0.04514354867943193 + 0.6824999999999998 + 1.0 + 0.19313984797592826 + 5 + + + + 0.09998859888505475 + 0.001067699166012432 + 0.7735 + 1.0 + 0.04223082219218105 + 1 + + + 0.19984596841848926 + 0.0063083873516208075 + 0.7507499999999999 + 1.0 + 0.08258278459127888 + 2 + + + 0.29941528681201485 + 0.015527961037171321 + 0.7279999999999999 + 1.0 + 0.12113667494984079 + 3 + + + 0.3985613369615038 + 0.02853539902833617 + 0.7052499999999998 + 1.0 + 0.1579664326475074 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.49675719636542215 + 0.04788598443637474 + 0.79625 + 1.0 + 0.21355606529756604 + 5 + + + + 0.09998859888505475 + 0.001067699166012432 + 0.79625 + 1.0 + 0.04271121305951322 + 1 + + + 0.1998404207843134 + 0.006403760625947382 + 0.79625 + 1.0 + 0.08542242611902644 + 2 + + + 0.29937333892879125 + 0.015998451561571623 + 0.79625 + 1.0 + 0.12813363917853965 + 3 + + + 0.39840580822051735 + 0.029834271540481672 + 0.79625 + 1.0 + 0.17084485223805285 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.49626161683721076 + 0.050925475111320645 + 0.9100000000000003 + 1.0 + 0.23723111702527633 + 5 + + + + 0.09998859888505475 + 0.001067699166012432 + 0.8190000000000001 + 1.0 + 0.043202904479743426 + 1 + + + 0.19983455004833936 + 0.006502511933242439 + 0.8417500000000001 + 1.0 + 0.08842048591898978 + 2 + + + 0.29932697688415044 + 0.016496943811754688 + 0.8645000000000002 + 1.0 + 0.13575445613920595 + 3 + + + 0.39822632620728615 + 0.031242069883365187 + 0.8872500000000002 + 1.0 + 0.18531679597946515 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.7168149858271075 + 0.09308452560070432 + 0.6824999999999998 + 2.000000000000001 + 0.27641497665505355 + 5 + + + + 0.10498745877356022 + 0.0011744690826136753 + 0.7735 + 1.2000000000000002 + 0.0443183437584235 + 1 + + + 0.22977474608571413 + 0.008301502100592932 + 0.7507499999999999 + 1.4000000000000004 + 0.09473533287164669 + 2 + + + 0.3739031221612934 + 0.02405268972692722 + 0.7279999999999999 + 1.6000000000000005 + 0.15061647529617625 + 3 + + + 0.536617767348453 + 0.05130897989771022 + 0.7052499999999998 + 1.8000000000000007 + 0.21136446118567337 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.715387786468145 + 0.09989339701332536 + 0.79625 + 2.000000000000001 + 0.3096562946814708 + 5 + + + + 0.10498745877356022 + 0.0011744690826136753 + 0.79625 + 1.2000000000000002 + 0.04484677371248888 + 1 + + + 0.22976578696690175 + 0.00844136041534184 + 0.79625 + 1.4000000000000004 + 0.0982357900368804 + 2 + + + 0.37381345733935856 + 0.024890558954123995 + 0.79625 + 1.6000000000000005 + 0.16016704897317458 + 3 + + + 0.5361894791844423 + 0.054063991663972716 + 0.79625 + 1.8000000000000007 + 0.2306405505213714 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.7136337397713569 + 0.10748536162084146 + 0.9100000000000003 + 2.000000000000001 + 0.34847496843666054 + 5 + + + + 0.10498745877356022 + 0.0011744690826136753 + 0.8190000000000001 + 1.2000000000000002 + 0.045387634274742114 + 1 + + + 0.22975628410205945 + 0.00858627512376934 + 0.8417500000000001 + 1.4000000000000004 + 0.10193540761945244 + 2 + + + 0.37371365170297116 + 0.025780590996568854 + 0.8645000000000002 + 1.6000000000000005 + 0.1705967936198724 + 3 + + + 0.5356887046156469 + 0.05706378973026624 + 0.8872500000000002 + 1.8000000000000007 + 0.2524032525427145 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.932220107876574 + 0.15715190296194664 + 0.6824999999999998 + 3.0000000000000004 + 0.35969010533417867 + 5 + + + + 0.1099863186620657 + 0.0012812389992149181 + 0.7735 + 1.4 + 0.04640586532466594 + 1 + + + 0.2596862224089239 + 0.010520764945648305 + 0.7507499999999999 + 1.7999999999999998 + 0.10688788115201447 + 2 + + + 0.44816632849804483 + 0.03427294686690692 + 0.7279999999999999 + 2.1999999999999997 + 0.18009627564251166 + 3 + + + 0.6734667516994062 + 0.08028987664431293 + 0.7052499999999998 + 2.6 + 0.2647624897238392 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.9288219353996048 + 0.16972376092281263 + 0.79625 + 3.0000000000000004 + 0.4057565240653755 + 5 + + + + 0.1099863186620657 + 0.0012812389992149181 + 0.79625 + 1.4 + 0.046982334365464534 + 1 + + + 0.2596727699026366 + 0.010713150370959565 + 0.79625 + 1.7999999999999998 + 0.11104915395473436 + 2 + + + 0.44800313130996283 + 0.035580354552078794 + 0.79625 + 2.1999999999999997 + 0.19220045876780945 + 3 + + + 0.6725614506327806 + 0.0850215286633461 + 0.79625 + 2.6 + 0.2904362488046898 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 0.9246054051530322 + 0.18374632615318892 + 0.9100000000000003 + 3.0000000000000004 + 0.45971881984804447 + 5 + + + + 0.1099863186620657 + 0.0012812389992149181 + 0.8190000000000001 + 1.4 + 0.04757236406974079 + 1 + + + 0.2596584747796522 + 0.010912592311773113 + 0.8417500000000001 + 1.7999999999999998 + 0.11545032931991507 + 2 + + + 0.44782061328462036 + 0.036971199701287774 + 0.8645000000000002 + 2.1999999999999997 + 0.2054391311005388 + 3 + + + 0.6714949634050951 + 0.09018267087651775 + 0.8872500000000002 + 2.6 + 0.3194897091059637 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 1.1421866378565075 + 0.23698260109443797 + 0.6824999999999998 + 3.999999999999999 + 0.44296523401330384 + 5 + + + + 0.11498517855057117 + 0.0013880089158161614 + 0.7735 + 1.6 + 0.04849338689090839 + 1 + + + 0.28957856012744165 + 0.012966029401175735 + 0.7507499999999999 + 2.2 + 0.1190404294323823 + 2 + + + 0.5221647667192739 + 0.0461829333593589 + 0.7279999999999999 + 2.8 + 0.20957607598884712 + 3 + + + 0.8088227833936622 + 0.11541567538358505 + 0.7052499999999998 + 3.3999999999999995 + 0.31816051826200514 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 1.1355679870502704 + 0.25687121775575517 + 0.79625 + 3.999999999999999 + 0.5018567534492802 + 5 + + + + 0.11498517855057117 + 0.0013880089158161614 + 0.79625 + 1.6 + 0.0491178950184402 + 1 + + + 0.2895593923255091 + 0.013218968606814478 + 0.79625 + 2.2 + 0.12386251787258833 + 2 + + + 0.521896849928075 + 0.048060903911937 + 0.79625 + 2.8 + 0.2242338685624444 + 3 + + + 0.8071816919095905 + 0.12262626548942761 + 0.79625 + 3.3999999999999995 + 0.3502319470880083 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 1.1273144966864042 + 0.27899798560156935 + 0.9100000000000003 + 3.999999999999999 + 0.5709626712594285 + 5 + + + + 0.11498517855057117 + 0.0013880089158161614 + 0.8190000000000001 + 1.6 + 0.04975709386473948 + 1 + + + 0.2895389934466288 + 0.013481284465613707 + 0.8417500000000001 + 2.2 + 0.12896525102037773 + 2 + + + 0.5215961964450047 + 0.050060457117088564 + 0.8645000000000002 + 2.8 + 0.24028146858120525 + 3 + + + 0.8052392752844125 + 0.1304940608779971 + 0.8872500000000002 + 3.3999999999999995 + 0.386576165669213 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 1.0 + 0.0 + 0 + + + 1.345547675251758 + 0.33212521737673195 + 0.6824999999999998 + 5.0 + 0.526240362692429 + 5 + + + + 0.11998403843907664 + 0.0014947788324174045 + 0.7735 + 1.7999999999999998 + 0.050580908457150825 + 1 + + + 0.31944992316922755 + 0.01563713458268914 + 0.7507499999999999 + 2.5999999999999996 + 0.1311929777127501 + 2 + + + 0.5958584442326313 + 0.059775909301325765 + 0.7279999999999999 + 3.3999999999999995 + 0.23905587633518255 + 3 + + + 0.942403516425542 + 0.15661090924816184 + 0.7052499999999998 + 4.199999999999999 + 0.371558546800171 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.27421216685933975 + 0.017097885348048254 + 0.7962499999999998 + 1.3877787807814457e-16 + 0.13812520162789457 + 5 + + + + 0.09498374232176512 + 0.0012095150801198838 + 0.88725 + 0.8 + 0.05051479231988343 + 1 + + + 0.16984444161396775 + 0.005713512914524443 + 0.8644999999999999 + 0.6000000000000001 + 0.08858575131363658 + 2 + + + 0.22459358365783338 + 0.010945094370691206 + 0.8417499999999999 + 0.40000000000000013 + 0.11525200260781479 + 3 + + + 0.25934459308585944 + 0.015109355495869494 + 0.8189999999999998 + 0.20000000000000015 + 0.13147030678027602 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.2741436321449146 + 0.017710736928653013 + 0.91 + 1.3877787807814457e-16 + 0.14784742619080785 + 5 + + + + 0.09498374232176512 + 0.0012095150801198838 + 0.91 + 0.8 + 0.05107456541136998 + 1 + + + 0.16983943531218787 + 0.005789667480745995 + 0.91 + 0.6000000000000001 + 0.09139659073613576 + 2 + + + 0.22456984025007856 + 0.011210707572538912 + 0.91 + 0.40000000000000013 + 0.12096607597429734 + 3 + + + 0.25929375525205384 + 0.0155942041374156 + 0.91 + 0.20000000000000015 + 0.1397830211258547 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.49552952080879364 + 0.05666307648330614 + 0.7962499999999998 + 1.0 + 0.24275686071203012 + 5 + + + + 0.09998193591307236 + 0.0013439056445776485 + 0.88725 + 1.0 + 0.053140730331369304 + 1 + + + 0.19975621544267502 + 0.007935399755202275 + 0.8644999999999999 + 1.0 + 0.10386282304659489 + 2 + + + 0.29907544138011627 + 0.019519500868142005 + 0.8417499999999999 + 1.0 + 0.15229628802375408 + 3 + + + 0.39772699847777176 + 0.0358443882632039 + 0.8189999999999998 + 1.0 + 0.19855873749894387 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.4948680793622454 + 0.06015595282415902 + 0.91 + 1.0 + 0.2688135021651051 + 5 + + + + 0.09998193591307236 + 0.0013439056445776485 + 0.91 + 1.0 + 0.05376270043302103 + 1 + + + 0.19974719414072803 + 0.008058579283439072 + 0.91 + 1.0 + 0.10752540086604206 + 2 + + + 0.2990074798426894 + 0.0201246173105733 + 0.91 + 1.0 + 0.16128810129906307 + 3 + + + 0.39747595741384967 + 0.037507152112067295 + 0.91 + 1.0 + 0.21505080173208407 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.7120936697182421 + 0.11662730412318768 + 0.7962499999999998 + 2.000000000000001 + 0.3473885197961658 + 5 + + + + 0.1049801295043796 + 0.0014782962090354136 + 0.88725 + 1.2000000000000002 + 0.05576666834285518 + 1 + + + 0.2296435390525112 + 0.01044145945543112 + 0.8644999999999999 + 1.4000000000000004 + 0.11913989477955322 + 2 + + + 0.373266240945053 + 0.030223925419893584 + 0.8417499999999999 + 1.6000000000000005 + 0.18934057343969346 + 3 + + + 0.5346602583530511 + 0.06439180275121847 + 0.8189999999999998 + 1.8000000000000007 + 0.26564716821761186 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.7098066050311808 + 0.12523420315384215 + 0.91 + 2.000000000000001 + 0.3897795781394026 + 5 + + + + 0.1049801295043796 + 0.0014782962090354136 + 0.91 + 1.2000000000000002 + 0.05645083545467208 + 1 + + + 0.2296289729730855 + 0.010622037945528245 + 0.91 + 1.4000000000000004 + 0.1236542109959484 + 2 + + + 0.37312108527478544 + 0.03130002041067925 + 0.91 + 1.6000000000000005 + 0.2016101266238289 + 3 + + + 0.533970214588133 + 0.06790576307078879 + 0.91 + 1.8000000000000007 + 0.29031858233831365 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.9220053184425354 + 0.1964521849461928 + 0.7962499999999998 + 3.0000000000000004 + 0.4520201788803012 + 5 + + + + 0.10997832309568684 + 0.0016126867734931783 + 0.88725 + 1.4 + 0.058392606354341056 + 1 + + + 0.2595035097905558 + 0.013231429421869556 + 0.8644999999999999 + 1.7999999999999998 + 0.1344169665125115 + 2 + + + 0.44710264236070074 + 0.043048737785551745 + 0.8417499999999999 + 2.1999999999999997 + 0.2263848588556327 + 3 + + + 0.6696934130698717 + 0.10065417916899438 + 0.8189999999999998 + 2.6 + 0.33273559893627963 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 0.9165798775755624 + 0.21219700353336868 + 0.91 + 3.0000000000000004 + 0.5107456541136998 + 5 + + + + 0.10997832309568684 + 0.0016126867734931783 + 0.91 + 1.4 + 0.05913897047632313 + 1 + + + 0.25948164193264356 + 0.013479752901095144 + 0.91 + 1.7999999999999998 + 0.13978302112585467 + 2 + + + 0.44683863500418936 + 0.04472539320709769 + 0.91 + 2.1999999999999997 + 0.24193215194859458 + 3 + + + 0.668237420632918 + 0.1066642764738921 + 0.91 + 2.6 + 0.36558636294454294 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 1.123423869838289 + 0.2954237646534862 + 0.7962499999999998 + 3.999999999999999 + 0.5566518379644367 + 5 + + + + 0.11497651668699407 + 0.001747077337950943 + 0.88725 + 1.6 + 0.06101854436582694 + 1 + + + 0.2893332277023095 + 0.01630501845975127 + 0.8644999999999999 + 2.2 + 0.14969403824546984 + 2 + + + 0.5205216162415301 + 0.05798244304056524 + 0.8417499999999999 + 2.8 + 0.2634291442715721 + 3 + + + 0.8023818657316667 + 0.14450823140705318 + 0.8189999999999998 + 3.3999999999999995 + 0.39982402965494757 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 1.0 + 0.0 + 0 + + + 1.1129018679829594 + 0.3200465358766587 + 0.91 + 3.999999999999999 + 0.6317117300879971 + 5 + + + + 0.11497651668699407 + 0.001747077337950943 + 0.91 + 1.6 + 0.06182710549797419 + 1 + + + 0.28930207425135235 + 0.016631401489313004 + 0.91 + 2.2 + 0.155911831255761 + 2 + + + 0.5200885072278264 + 0.06038693683020054 + 0.91 + 2.8 + 0.28225417727336044 + 3 + + + 0.799747582623634 + 0.1536227877365586 + 0.91 + 3.3999999999999995 + 0.4408541435507724 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.5500000000000002 + 0.0 + 0.0 + 2.7755575615628914e-16 + 0.0 + 5 + + + + 0.19 + 0.0 + 0.0 + 1.6 + 0.0 + 1 + + + 0.34 + 0.0 + 0.0 + 1.2000000000000002 + 0.0 + 2 + + + 0.45000000000000007 + 0.0 + 0.0 + 0.8000000000000003 + 0.0 + 3 + + + 0.5200000000000001 + 0.0 + 0.0 + 0.4000000000000003 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.5499979138413031 + 0.0009732441733405645 + 0.11374999999999999 + 2.7755575615628914e-16 + 0.007854343932087383 + 5 + + + + 0.19 + 0.0 + 0.022750000000000003 + 1.6 + 0.0004278859508317765 + 1 + + + 0.3399999432237332 + 0.00011743779270462101 + 0.045500000000000006 + 1.2000000000000002 + 0.002187415737773826 + 2 + + + 0.449999522593807 + 0.0004151415123464613 + 0.06825 + 0.8000000000000003 + 0.00451898776154151 + 3 + + + 0.5199986333408324 + 0.0007657517794316859 + 0.091 + 0.4000000000000003 + 0.006662215406893125 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.7749999999999997 + 0.0 + 0.0 + 0.9999999999999992 + 0.0 + 5 + + + + 0.195 + 0.0 + 0.0 + 1.7999999999999998 + 0.0 + 1 + + + 0.37 + 0.0 + 0.0 + 1.5999999999999996 + 0.0 + 2 + + + 0.5249999999999999 + 0.0 + 0.0 + 1.3999999999999995 + 0.0 + 3 + + + 0.6599999999999998 + 0.0 + 0.0 + 1.1999999999999993 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.7749887256481206 + 0.002848527151988614 + 0.11374999999999999 + 0.9999999999999992 + 0.014644684465808057 + 5 + + + + 0.195 + 0.0 + 0.022750000000000003 + 1.7999999999999998 + 0.00045165739254465287 + 1 + + + 0.36999991815967115 + 0.00015179003626913552 + 0.045500000000000006 + 1.5999999999999996 + 0.0025203020818942374 + 2 + + + 0.5249990512176637 + 0.000656612620924636 + 0.06825 + 1.3999999999999995 + 0.005827365448744199 + 3 + + + 0.6599958715870378 + 0.0015732878206852021 + 0.091 + 1.1999999999999993 + 0.009994877479743383 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.9999999999999999 + 0.0 + 0.0 + 2.0 + 0.0 + 5 + + + + 0.2 + 0.0 + 0.0 + 2.0 + 0.0 + 1 + + + 0.4 + 0.0 + 0.0 + 2.0 + 0.0 + 2 + + + 0.6 + 0.0 + 0.0 + 2.0 + 0.0 + 3 + + + 0.7999999999999999 + 0.0 + 0.0 + 2.0 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 0.9999672384210029 + 0.005710693120430923 + 0.11374999999999999 + 2.0 + 0.02143502499952875 + 5 + + + + 0.2 + 0.0 + 0.022750000000000003 + 2.0 + 0.00047542883425752934 + 1 + + + 0.39999988696617683 + 0.0001901837894019362 + 0.045500000000000006 + 2.0 + 0.0028531884260146493 + 2 + + + 0.5999983488933142 + 0.0009511139631654807 + 0.06825 + 2.0 + 0.007135743135946891 + 3 + + + 0.7999908103711009 + 0.0026639286252371696 + 0.091 + 2.0 + 0.01332753955259365 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.225 + 0.0 + 0.0 + 3.000000000000001 + 0.0 + 5 + + + + 0.20500000000000002 + 0.0 + 0.0 + 2.2 + 0.0 + 1 + + + 0.43000000000000005 + 0.0 + 0.0 + 2.4000000000000004 + 0.0 + 2 + + + 0.675 + 0.0 + 0.0 + 2.6000000000000005 + 0.0 + 3 + + + 0.9400000000000001 + 0.0 + 0.0 + 2.8000000000000007 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.2249282418474254 + 0.009559661180157608 + 0.11374999999999999 + 3.000000000000001 + 0.028225365533249436 + 5 + + + + 0.20500000000000002 + 0.0 + 0.022750000000000003 + 2.2 + 0.0004992002759704059 + 1 + + + 0.4299998489904506 + 0.0002326190510693354 + 0.045500000000000006 + 2.4000000000000004 + 0.0031860747701350613 + 2 + + + 0.6749973701411398 + 0.001298645317110568 + 0.06825 + 2.6000000000000005 + 0.008444120823149583 + 3 + + + 0.9399827578182788 + 0.0040376675576678615 + 0.091 + 2.8000000000000007 + 0.016660201625443915 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.4500000000000006 + 0.0 + 0.0 + 4.000000000000002 + 0.0 + 5 + + + + 0.21000000000000002 + 0.0 + 0.0 + 2.4000000000000004 + 0.0 + 1 + + + 0.4600000000000001 + 0.0 + 0.0 + 2.8000000000000007 + 0.0 + 2 + + + 0.7500000000000001 + 0.0 + 0.0 + 3.200000000000001 + 0.0 + 3 + + + 1.0800000000000003 + 0.0 + 0.0 + 3.6000000000000014 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.4498665261344117 + 0.014395322146271605 + 0.11374999999999999 + 4.000000000000002 + 0.03501570606697013 + 5 + + + + 0.21000000000000002 + 0.0 + 0.022750000000000003 + 2.4000000000000004 + 0.0005229717176832824 + 1 + + + 0.4599998035796925 + 0.0002790958201363314 + 0.045500000000000006 + 2.8000000000000007 + 0.0035189611142554737 + 2 + + + 0.7499960694817301 + 0.001699206421430348 + 0.06825 + 3.200000000000001 + 0.009752498510352276 + 3 + + + 1.0799710220726522 + 0.005694496252948338 + 0.091 + 3.6000000000000014 + 0.019992863698294186 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.6749999999999996 + 0.0 + 0.0 + 4.999999999999998 + 0.0 + 5 + + + + 0.215 + 0.0 + 0.0 + 2.5999999999999996 + 0.0 + 1 + + + 0.49 + 0.0 + 0.0 + 3.1999999999999993 + 0.0 + 2 + + + 0.8249999999999998 + 0.0 + 0.0 + 3.799999999999999 + 0.0 + 3 + + + 1.2199999999999998 + 0.0 + 0.0 + 4.399999999999999 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.6747768821628255 + 0.020217538550744305 + 0.11374999999999999 + 4.999999999999998 + 0.04180604660069079 + 5 + + + + 0.215 + 0.0 + 0.022750000000000003 + 2.5999999999999996 + 0.0005467431593961587 + 1 + + + 0.4899997500811029 + 0.00032961409536660745 + 0.045500000000000006 + 3.1999999999999993 + 0.0038518474583758844 + 2 + + + 0.8249944014359168 + 0.002152796975424334 + 0.06825 + 3.799999999999999 + 0.011060876197554961 + 3 + + + 1.2199549113014452 + 0.007634404616492695 + 0.091 + 4.399999999999999 + 0.023325525771144436 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.9 + 0.0 + 0.0 + 6.000000000000001 + 0.0 + 5 + + + + 0.22 + 0.0 + 0.0 + 2.8 + 0.0 + 1 + + + 0.52 + 0.0 + 0.0 + 3.5999999999999996 + 0.0 + 2 + + + 0.8999999999999999 + 0.0 + 0.0 + 4.3999999999999995 + 0.0 + 3 + + + 1.3599999999999999 + 0.0 + 0.0 + 5.2 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 1.8996541016416482 + 0.027026144646511138 + 0.11374999999999999 + 6.000000000000001 + 0.04859638713441148 + 5 + + + + 0.22 + 0.0 + 0.022750000000000003 + 2.8 + 0.0005705146011090352 + 1 + + + 0.5199996878418829 + 0.0003841738754225331 + 0.045500000000000006 + 3.5999999999999996 + 0.004184733802496296 + 2 + + + 0.899992320524808 + 0.00265941663902133 + 0.06825 + 4.3999999999999995 + 0.012369253884757653 + 3 + + + 1.359933733699348 + 0.009857380824221083 + 0.091 + 5.2 + 0.0266581878439947 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 2.122506704576892 + 0.0 + 0.0 + 6.876717391979616 + 0.0 + 5 + + + + 0.225 + 0.0 + 0.0 + 3.0 + 0.0 + 1 + + + 0.55 + 0.0 + 0.0 + 4.0 + 0.0 + 2 + + + 0.975 + 0.0 + 0.0 + 5.0 + 0.0 + 3 + + + 1.5 + 0.0 + 0.0 + 5.997113636363636 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 2.0 + 0.0 + 0 + + + 2.1220018361658233 + 0.034717548918394514 + 0.11374999999999999 + 6.876717391979616 + 0.05528036596305397 + 5 + + + + 0.225 + 0.0 + 0.022750000000000003 + 3.0 + 0.0005942860428219117 + 1 + + + 0.549999616209233 + 0.00044277515886516306 + 0.045500000000000006 + 4.0 + 0.004517620146616708 + 2 + + + 0.9749897812698203 + 0.003219065032779668 + 0.06825 + 5.0 + 0.013677631571960343 + 3 + + + 1.4999067974928333 + 0.012363411322633359 + 0.091 + 5.997113636363636 + 0.02999084991684496 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.5499637296676682 + 0.005320624386558012 + 3.469446951953614e-18 + 2.7755575615628914e-16 + 0.01835537549718328 + 5 + + + + 0.18999897410513863 + 0.0004297208658973709 + 0.09100000000000001 + 1.6 + 0.00863901150747678 + 1 + + + 0.3399912058718604 + 0.0019391181467160487 + 0.06825000000000002 + 1.2000000000000002 + 0.014024487800632377 + 2 + + + 0.44997911290457393 + 0.003567458349645169 + 0.04550000000000001 + 0.8000000000000003 + 0.016928424133736204 + 3 + + + 0.5199686879022576 + 0.00477522338146144 + 0.022750000000000006 + 0.4000000000000003 + 0.018117636468333396 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.549945909667274 + 0.00630224948862724 + 0.11375 + 2.7755575615628914e-16 + 0.026260819363580497 + 5 + + + + 0.18999897410513863 + 0.0004297208658973709 + 0.11375 + 1.6 + 0.009071919416509627 + 1 + + + 0.3399898653844856 + 0.002057856715553764 + 0.11375 + 1.2000000000000002 + 0.016233961061122487 + 2 + + + 0.4499728405077973 + 0.003986732429124028 + 0.11375 + 0.8000000000000003 + 0.02148612493383859 + 3 + + + 0.5199553975720805 + 0.005547927351593114 + 0.11375 + 0.4000000000000003 + 0.024828411034657924 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.5499236276426631 + 0.0072921355370150764 + 0.22749999999999998 + 2.7755575615628914e-16 + 0.03426989003689388 + 5 + + + + 0.18999897410513863 + 0.0004297208658973709 + 0.1365 + 1.6 + 0.009505953979688755 + 1 + + + 0.33998840291851495 + 0.0021770432894732553 + 0.15925 + 1.2000000000000002 + 0.01845646004607262 + 2 + + + 0.4499655462632074 + 0.004408473033841565 + 0.182 + 0.8000000000000003 + 0.026084566041177343 + 3 + + + 0.5199391841912975 + 0.006326450124681607 + 0.20475 + 0.4000000000000003 + 0.03161648800341153 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.7749147512236504 + 0.009984917177437113 + 3.469446951953614e-18 + 0.9999999999999992 + 0.022282547463226967 + 5 + + + + 0.19499891711097966 + 0.0004535942473361137 + 0.09100000000000001 + 1.7999999999999998 + 0.008853695789573162 + 1 + + + 0.3699889744408418 + 0.002294710012381348 + 0.06825000000000002 + 1.5999999999999996 + 0.01512078844519014 + 2 + + + 0.5249684676515756 + 0.004809733437419968 + 0.04550000000000001 + 1.3999999999999995 + 0.01919100422448829 + 3 + + + 0.6599418893362036 + 0.007486926980247766 + 0.022750000000000006 + 1.1999999999999993 + 0.021450473168112934 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.7748468441853419 + 0.012854500237096791 + 0.11375 + 0.9999999999999992 + 0.037003881830499775 + 5 + + + + 0.19499891711097966 + 0.0004535942473361137 + 0.11375 + 1.7999999999999998 + 0.00931065413799672 + 1 + + + 0.3699871463770736 + 0.0024481750412760437 + 0.11375 + 1.5999999999999996 + 0.017666369390045056 + 2 + + + 0.5249573513347895 + 0.005472746461404738 + 0.11375 + 1.3999999999999995 + 0.02506714575614501 + 3 + + + 0.6599091309735768 + 0.00907362758745837 + 0.11375 + 1.1999999999999993 + 0.03151298323629658 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.7747548987888004 + 0.015754199711126654 + 0.22749999999999998 + 0.9999999999999992 + 0.05195624888447098 + 5 + + + + 0.19499891711097966 + 0.0004535942473361137 + 0.1365 + 1.7999999999999998 + 0.00976880173246358 + 1 + + + 0.3699851427586338 + 0.0026022290969633308 + 0.15925 + 1.5999999999999996 + 0.02022723068965857 + 2 + + + 0.5249442082521858 + 0.006139883321966063 + 0.182 + 1.3999999999999995 + 0.030998133930514402 + 3 + + + 0.6598675654378166 + 0.010673732199710987 + 0.20475 + 1.1999999999999993 + 0.04170202360936528 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.9998410042909709 + 0.01573325229358432 + 3.469446951953614e-18 + 2.0 + 0.02620971942927066 + 5 + + + + 0.1999988601168207 + 0.0004774676287748566 + 0.09100000000000001 + 2.0 + 0.009068380071669543 + 1 + + + 0.39998645095597113 + 0.002672475564825119 + 0.06825000000000002 + 2.0 + 0.0162170890897479 + 2 + + + 0.5999551112681542 + 0.006201395365746841 + 0.04550000000000001 + 2.0 + 0.02145358431524038 + 3 + + + 0.7999048241997448 + 0.010682029977545622 + 0.022750000000000006 + 2.0 + 0.024783309867892477 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.9996751658796997 + 0.021482451425853873 + 0.11375 + 2.0 + 0.047746944297419075 + 5 + + + + 0.1999988601168207 + 0.0004774676287748566 + 0.11375 + 2.0 + 0.009549388859483816 + 1 + + + 0.39998404181739583 + 0.0028647513471654253 + 0.11375 + 2.0 + 0.019098777718967633 + 2 + + + 0.5999373084260858 + 0.007161633458448071 + 0.11375 + 2.0 + 0.02864816657845145 + 3 + + + 0.7998404261775928 + 0.013367722129364656 + 0.11375 + 2.0 + 0.038197555437935266 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 0.9994396388195969 + 0.027296821499104083 + 0.22749999999999998 + 2.0 + 0.06964260773204811 + 5 + + + + 0.1999988601168207 + 0.0004774676287748566 + 0.1365 + 2.0 + 0.010031649485238405 + 1 + + + 0.3999813905281855 + 0.0030577750813535103 + 0.15925 + 2.0 + 0.021998001333244525 + 2 + + + 0.5999159839222944 + 0.00812805926864486 + 0.182 + 2.0 + 0.035911701819851476 + 3 + + + 0.7997564607928351 + 0.016077410982390038 + 0.20475 + 2.0 + 0.05178755921531905 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.224737694219903 + 0.022565511146086535 + 3.469446951953614e-18 + 3.000000000000001 + 0.03013689139531435 + 5 + + + + 0.20499880312266172 + 0.0005013410102135995 + 0.09100000000000001 + 2.2 + 0.009283064353765925 + 1 + + + 0.42998361804797863 + 0.003072414569937349 + 0.06825000000000002 + 2.4000000000000004 + 0.017313389734305663 + 2 + + + 0.6749387457392176 + 0.007742438441873129 + 0.04550000000000001 + 2.6000000000000005 + 0.023716164405992467 + 3 + + + 0.9398558911102346 + 0.01436049596383705 + 0.022750000000000006 + 2.8000000000000007 + 0.02811614656767202 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.2244111883402224 + 0.03218531695372315 + 0.11375 + 3.000000000000001 + 0.05849000676433838 + 5 + + + + 0.20499880312266172 + 0.0005013410102135995 + 0.11375 + 2.2 + 0.009788123580970913 + 1 + + + 0.4299805269157625 + 0.003307585259465189 + 0.11375 + 2.4000000000000004 + 0.020531186047890206 + 2 + + + 0.6749121365905277 + 0.009053379635066305 + 0.11375 + 2.6000000000000005 + 0.032229187400757885 + 3 + + + 0.9397449168599556 + 0.01843007032785008 + 0.11375 + 2.8000000000000007 + 0.04488212763957394 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.2239323046490824 + 0.04191746419427676 + 0.22749999999999998 + 3.000000000000001 + 0.08732896657962526 + 5 + + + + 0.20499880312266172 + 0.0005013410102135995 + 0.1365 + 2.2 + 0.01029449723801323 + 1 + + + 0.42997711264053323 + 0.0035436806822721186 + 0.15925 + 2.4000000000000004 + 0.02376877197683048 + 2 + + + 0.6748799250034851 + 0.010372973465939364 + 0.182 + 2.6000000000000005 + 0.040825269709188546 + 3 + + + 0.9395972812537653 + 0.02253712636469362 + 0.20475 + 2.8000000000000007 + 0.061873094821272824 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.449600026900888 + 0.030481554857258737 + 3.469446951953614e-18 + 4.000000000000002 + 0.03406406336135805 + 5 + + + + 0.20999874612850278 + 0.0005252143916523424 + 0.09100000000000001 + 2.4000000000000004 + 0.009497748635862308 + 1 + + + 0.45998045834777446 + 0.003494526780506841 + 0.06825000000000002 + 2.8000000000000007 + 0.01840969037886343 + 2 + + + 0.7499190730613271 + 0.009432856390845037 + 0.04550000000000001 + 3.200000000000001 + 0.02597874449674456 + 3 + + + 1.0797934888099394 + 0.018522283374082984 + 0.022750000000000006 + 3.6000000000000014 + 0.03144898326745157 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.4490352335030976 + 0.04496212407956459 + 0.11375 + 4.000000000000002 + 0.06923306923125769 + 5 + + + + 0.20999874612850278 + 0.0005252143916523424 + 0.11375 + 2.4000000000000004 + 0.010026858302458006 + 1 + + + 0.4599765768828313 + 0.0037766763818344795 + 0.11375 + 2.8000000000000007 + 0.02196359437681278 + 2 + + + 0.7498812606779427 + 0.011147969588234287 + 0.11375 + 3.200000000000001 + 0.03581020822306431 + 3 + + + 1.079618237564415 + 0.024260506778417713 + 0.11375 + 3.6000000000000014 + 0.05156669984121262 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.448187396441209 + 0.0596129093858747 + 0.22749999999999998 + 4.000000000000002 + 0.1050153254272024 + 5 + + + + 0.20999874612850278 + 0.0005252143916523424 + 0.1365 + 2.4000000000000004 + 0.010557344990788054 + 1 + + + 0.4599722755096518 + 0.004059945303455363 + 0.15925 + 2.8000000000000007 + 0.025539542620416435 + 2 + + + 0.7498350833330896 + 0.012874595009913836 + 0.182 + 3.200000000000001 + 0.04573883759852562 + 3 + + + 1.0793814410641707 + 0.030052447866474243 + 0.20475 + 3.6000000000000014 + 0.07195863042722661 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.6744232088482818 + 0.03948122426303221 + 3.469446951953614e-18 + 4.999999999999998 + 0.03799123532740173 + 5 + + + + 0.2149986891343438 + 0.000549087773091085 + 0.09100000000000001 + 2.5999999999999996 + 0.009712432917958688 + 1 + + + 0.4899769544864584 + 0.003938811936221344 + 0.06825000000000002 + 3.1999999999999993 + 0.01950599102342119 + 2 + + + 0.8248957952438175 + 0.011272642355531028 + 0.04550000000000001 + 3.799999999999999 + 0.02824132458749664 + 3 + + + 1.2197160161823644 + 0.02316734548814307 + 0.022750000000000006 + 4.399999999999999 + 0.03478181996723109 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.6735276334152789 + 0.059811713509480446 + 0.11375 + 4.999999999999998 + 0.07997613169817694 + 5 + + + + 0.2149986891343438 + 0.000549087773091085 + 0.11375 + 2.5999999999999996 + 0.010265593023945103 + 1 + + + 0.4899721669296272 + 0.004272024295348615 + 0.11375 + 3.1999999999999993 + 0.023396002705735348 + 2 + + + 0.8248441055836446 + 0.01344538629720922 + 0.11375 + 3.799999999999999 + 0.039391229045370735 + 3 + + + 1.2194560238422656 + 0.030858841326817 + 0.11375 + 4.399999999999999 + 0.058251272042851264 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.6721594678296645 + 0.080379257684589 + 0.22749999999999998 + 4.999999999999998 + 0.12270168427477947 + 5 + + + + 0.2149986891343438 + 0.000549087773091085 + 0.1365 + 2.5999999999999996 + 0.010820192743562877 + 1 + + + 0.48996684555016434 + 0.0046065683127479795 + 0.15925 + 3.1999999999999993 + 0.02731031326400238 + 2 + + + 0.8247805108685746 + 0.0156328895010487 + 0.182 + 3.799999999999999 + 0.05065240548786267 + 3 + + + 1.2191003582890512 + 0.038622874664319296 + 0.20475 + 4.399999999999999 + 0.08204416603318034 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.8992024472840998 + 0.04956433991568338 + 3.469446951953614e-18 + 6.000000000000001 + 0.04191840729344542 + 5 + + + + 0.21999863214018484 + 0.0005729611545298279 + 0.09100000000000001 + 2.8 + 0.009927117200055069 + 1 + + + 0.5199730890953298 + 0.004405269763667709 + 0.06825000000000002 + 3.5999999999999996 + 0.02060229166797895 + 2 + + + 0.8998686143099195 + 0.013261788896647447 + 0.04550000000000001 + 4.3999999999999995 + 0.03050390467824873 + 3 + + + 1.359621872268581 + 0.028295630431246832 + 0.022750000000000006 + 5.2 + 0.03811465666701063 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.8978687319980465 + 0.07673273950064499 + 0.11375 + 6.000000000000001 + 0.09071919416509623 + 5 + + + + 0.21999863214018484 + 0.0005729611545298279 + 0.11375 + 2.8 + 0.010504327745432196 + 1 + + + 0.5199672722675629 + 0.004793628558499413 + 0.11375 + 3.5999999999999996 + 0.024828411034657917 + 2 + + + 0.8998000962529337 + 0.015945611123662863 + 0.11375 + 4.3999999999999995 + 0.04297224986767716 + 3 + + + 1.3592539123919394 + 0.03822485907510807 + 0.11375 + 5.2 + 0.06493584424448993 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 1.8958031361257035 + 0.1042119296010364 + 0.22749999999999998 + 6.000000000000001 + 0.14038804312235661 + 5 + + + + 0.21999863214018484 + 0.0005729611545298279 + 0.1365 + 2.8 + 0.011083040496337702 + 1 + + + 0.5199607891773801 + 0.005183549042103918 + 0.15925 + 3.5999999999999996 + 0.02908108390758834 + 2 + + + 0.8997152597002999 + 0.01864781904469988 + 0.182 + 4.3999999999999995 + 0.05556597337719974 + 3 + + + 1.358745455389879 + 0.04824783562508621 + 0.20475 + 5.2 + 0.0921297016391341 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 2.1214421029434956 + 0.06062025310718812 + 3.469446951953614e-18 + 6.876717391979616 + 0.045833039106279054 + 5 + + + + 0.22499857514602586 + 0.0005968345359685708 + 0.09100000000000001 + 3.0 + 0.010141801482151451 + 1 + + + 0.5499688448058966 + 0.004893899976332016 + 0.06825000000000002 + 4.0 + 0.021698592312536714 + 2 + + + 0.9748372322978771 + 0.015400287992786131 + 0.04550000000000001 + 5.0 + 0.03276648476900082 + 3 + + + 1.4995094562835465 + 0.03390708117451567 + 0.022750000000000006 + 5.997113636363636 + 0.041447493366790183 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 2.1195548221765073 + 0.09550949435098688 + 0.11375 + 6.876717391979616 + 0.10134320939433139 + 5 + + + + 0.22499857514602586 + 0.0005968345359685708 + 0.11375 + 3.0 + 0.010743062466919293 + 1 + + + 0.549961868108458 + 0.0053414887071955445 + 0.11375 + 4.0 + 0.02626081936358049 + 2 + + + 0.9747486576855935 + 0.018648623811826075 + 0.11375 + 5.0 + 0.0465532706899836 + 3 + + + 1.4990075411985575 + 0.046358320388508574 + 0.11375 + 5.997113636363636 + 0.07162041644612861 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.11375 + 2.0 + 0.0 + 0 + + + 2.1166003594542127 + 0.13078649643174783 + 0.22749999999999998 + 6.876717391979616 + 0.1578463326823111 + 5 + + + + 0.22499857514602586 + 0.0005968345359685708 + 0.1365 + 3.0 + 0.011345888249112528 + 1 + + + 0.5499540728073303 + 0.005790886787587043 + 0.15925 + 4.0 + 0.03085185455117429 + 2 + + + 0.9746383820642681 + 0.021919342251603982 + 0.182 + 5.0 + 0.06047954126653682 + 3 + + + 1.4983081597993373 + 0.0589266893441128 + 0.20475 + 5.997113636363636 + 0.10221523724508787 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.5498174544097039 + 0.01175310157539991 + 0.11375000000000005 + 2.7755575615628914e-16 + 0.045048388566293354 + 5 + + + + 0.18999578719556026 + 0.0008707967911237168 + 0.20475000000000002 + 1.6 + 0.017934139899910304 + 1 + + + 0.339961262490369 + 0.00404668367401426 + 0.18200000000000002 + 1.2000000000000002 + 0.03060626432605574 + 2 + + + 0.449902152171317 + 0.0076434713963473375 + 0.15925000000000003 + 0.8000000000000003 + 0.03882182427191645 + 3 + + + 0.5198461747104359 + 0.01044080223737439 + 0.13650000000000004 + 0.4000000000000003 + 0.04337457351518455 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.5497779012552041 + 0.012768996835157082 + 0.2275 + 2.7755575615628914e-16 + 0.053216189791265044 + 5 + + + + 0.18999578719556026 + 0.0008707967911237168 + 0.2275 + 1.6 + 0.018383774655164282 + 1 + + + 0.33995838362042635 + 0.004169909717538181 + 0.2275 + 1.2000000000000002 + 0.03289728096187293 + 2 + + + 0.44988847684695443 + 0.008078041674812226 + 0.2275 + 0.8000000000000003 + 0.04354051892012594 + 3 + + + 0.5198168568747132 + 0.011240903028600206 + 0.2275 + 0.4000000000000003 + 0.05031348852992332 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.5497329476839046 + 0.013802283049276925 + 0.3412500000000002 + 2.7755575615628914e-16 + 0.061602435188162684 + 5 + + + + 0.18999578719556026 + 0.0008707967911237168 + 0.25025000000000003 + 1.6 + 0.018835783903684292 + 1 + + + 0.3399553554579088 + 0.0042940796272204155 + 0.2730000000000001 + 1.2000000000000002 + 0.03521575094895859 + 2 + + + 0.4498735625007326 + 0.008517806677372494 + 0.2957500000000001 + 0.8000000000000003 + 0.0483450832861694 + 3 + + + 0.5197840014148319 + 0.012053255280737484 + 0.31850000000000017 + 0.4000000000000003 + 0.057415347013244716 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.7745251648104516 + 0.02307540212007464 + 0.11375000000000005 + 0.9999999999999992 + 0.059795986369869325 + 5 + + + + 0.19499555315086917 + 0.00091917439063059 + 0.20475000000000002 + 1.7999999999999998 + 0.018392943734842036 + 1 + + + 0.3699511490831956 + 0.004801532662649157 + 0.18200000000000002 + 1.5999999999999996 + 0.033160596836726175 + 2 + + + 0.5248492161749471 + 0.010401678377305268 + 0.15925000000000003 + 1.3999999999999995 + 0.04471477201192333 + 3 + + + 0.6596999093457571 + 0.016741244117218734 + 0.13650000000000004 + 1.1999999999999993 + 0.053460302452668786 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.7743711908676804 + 0.026040390373551263 + 0.2275 + 0.9999999999999992 + 0.07498644925132797 + 5 + + + + 0.19499555315086917 + 0.00091917439063059 + 0.2275 + 1.7999999999999998 + 0.018867558198721237 + 1 + + + 0.3699472186319006 + 0.004960788100774813 + 0.2275 + 1.5999999999999996 + 0.03579998222321465 + 2 + + + 0.5248248781588071 + 0.011088682177245462 + 0.2275 + 1.3999999999999995 + 0.05079727207348025 + 3 + + + 0.6596268988109187 + 0.018382961183539385 + 0.2275 + 1.1999999999999993 + 0.06385942774951801 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.7741883571700559 + 0.029068711168941434 + 0.3412500000000002 + 0.9999999999999992 + 0.09066395529405558 + 5 + + + + 0.19499555315086917 + 0.00091917439063059 + 0.25025000000000003 + 1.7999999999999998 + 0.019344679072159025 + 1 + + + 0.36994307414348443 + 0.005121284452307937 + 0.2730000000000001 + 1.5999999999999996 + 0.03847157290005894 + 2 + + + 0.5247980949560299 + 0.011784369222898796 + 0.2957500000000001 + 1.3999999999999995 + 0.05699537474516764 + 3 + + + 0.6595432994337616 + 0.020052884469295026 + 0.31850000000000017 + 1.1999999999999993 + 0.07452526704257785 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.9990476545158509 + 0.03757631694159316 + 0.11375000000000005 + 2.0 + 0.07454358417344531 + 5 + + + + 0.19999531910617807 + 0.000967551990137463 + 0.20475000000000002 + 2.0 + 0.018851747569773772 + 1 + + + 0.39993965558118366 + 0.005605339262071225 + 0.18200000000000002 + 2.0 + 0.03571492934739662 + 2 + + + 0.5997816927964532 + 0.013515367717442703 + 0.15925000000000003 + 2.0 + 0.05060771975193022 + 3 + + + 0.7994894273262266 + 0.02430286911457368 + 0.13650000000000004 + 2.0 + 0.06354603139015304 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.9986664946799061 + 0.04350995593693457 + 0.2275 + 2.0 + 0.09675670871139097 + 5 + + + + 0.19999531910617807 + 0.000967551990137463 + 0.2275 + 2.0 + 0.01935134174227819 + 1 + + + 0.39993447055395936 + 0.005804859048491397 + 0.2275 + 2.0 + 0.03870268348455638 + 2 + + + 0.59974258458057 + 0.014510109783799508 + 0.2275 + 2.0 + 0.058054025226834574 + 3 + + + 0.7993448404918682 + 0.027080044404006465 + 0.2275 + 2.0 + 0.07740536696911277 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 0.998202175298466 + 0.04958044642713322 + 0.3412500000000002 + 2.0 + 0.11972547539994856 + 5 + + + + 0.19999531910617807 + 0.000967551990137463 + 0.25025000000000003 + 2.0 + 0.01985357424063376 + 1 + + + 0.39992899126299203 + 0.006005954477819242 + 0.2730000000000001 + 2.0 + 0.0417273948511593 + 2 + + + 0.599699244239121 + 0.015517877588046082 + 0.2957500000000001 + 2.0 + 0.0656456662041659 + 3 + + + 0.799176841964332 + 0.029907681656021805 + 0.31850000000000017 + 2.0 + 0.09163518707191104 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.223340691487085 + 0.05525296605337159 + 0.11375000000000005 + 3.000000000000001 + 0.08929118197702131 + 5 + + + + 0.204995085061487 + 0.0010159295896443362 + 0.20475000000000002 + 2.2 + 0.019310551404705507 + 1 + + + 0.4299266964988868 + 0.006458101001784927 + 0.18200000000000002 + 2.4000000000000004 + 0.03826926185806707 + 2 + + + 0.6746978504433905 + 0.01698446403173387 + 0.15925000000000003 + 2.6000000000000005 + 0.056500667491937114 + 3 + + + 0.9392033234558852 + 0.03312504470465001 + 0.13650000000000004 + 2.8000000000000007 + 0.0736317603276373 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.2225831738011 + 0.06517115755764802 + 0.2275 + 3.000000000000001 + 0.11852696817145394 + 5 + + + + 0.204995085061487 + 0.0010159295896443362 + 0.2275 + 2.2 + 0.01983512528583515 + 1 + + + 0.429920037623858 + 0.006702119450801539 + 0.2275 + 2.4000000000000004 + 0.041605384745898116 + 2 + + + 0.6746392362110141 + 0.018342209814298877 + 0.2275 + 2.6000000000000005 + 0.06531077838018891 + 3 + + + 0.9389527807976183 + 0.037330982908048704 + 0.2275 + 2.8000000000000007 + 0.09095130618870752 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.2216446453526055 + 0.0753248192103818 + 0.3412500000000002 + 3.000000000000001 + 0.1487869955058415 + 5 + + + + 0.204995085061487 + 0.0010159295896443362 + 0.25025000000000003 + 2.2 + 0.02036246940910849 + 1 + + + 0.42991298717085924 + 0.006948085846790797 + 0.2730000000000001 + 2.4000000000000004 + 0.04498321680225965 + 2 + + + 0.6745739102985462 + 0.019718165127128894 + 0.2957500000000001 + 2.6000000000000005 + 0.07429595766316416 + 3 + + + 0.9386585362064874 + 0.041615676024696326 + 0.31850000000000017 + 2.8000000000000007 + 0.10874510710124421 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.4473600872406753 + 0.07610186311039335 + 0.11375000000000005 + 4.000000000000002 + 0.10403877978059732 + 5 + + + + 0.2099948510167959 + 0.0010643071891512095 + 0.20475000000000002 + 2.4000000000000004 + 0.01976935523963724 + 1 + + + 0.45991218635510245 + 0.007359815267383614 + 0.18200000000000002 + 2.8000000000000007 + 0.04082359436873751 + 2 + + + 0.7495959579049142 + 0.020808883611505964 + 0.15925000000000003 + 3.200000000000001 + 0.062393615231944005 + 3 + + + 1.07883019863766 + 0.04320703645505478 + 0.13650000000000004 + 3.6000000000000014 + 0.08371748926512156 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.44604072993452 + 0.09101591101859954 + 0.2275 + 4.000000000000002 + 0.14029722763151692 + 5 + + + + 0.2099948510167959 + 0.0010643071891512095 + 0.2275 + 2.4000000000000004 + 0.0203189088293921 + 1 + + + 0.45990381808471226 + 0.007652566009951798 + 0.2275 + 2.8000000000000007 + 0.04450808600723984 + 2 + + + 0.7495124738398448 + 0.022584854139045284 + 0.2275 + 3.200000000000001 + 0.07256753153354323 + 3 + + + 1.0784328332347002 + 0.04913440130888275 + 0.2275 + 3.6000000000000014 + 0.10449724540830226 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.44438636825422 + 0.10628592494688292 + 0.3412500000000002 + 4.000000000000002 + 0.17784851561173454 + 5 + + + + 0.2099948510167959 + 0.0010643071891512095 + 0.25025000000000003 + 2.4000000000000004 + 0.020871364577583228 + 1 + + + 0.4598949422294306 + 0.007947674461720101 + 0.2730000000000001 + 2.8000000000000007 + 0.04823903875336001 + 2 + + + 0.7494189942510573 + 0.024385044700134407 + 0.2957500000000001 + 3.200000000000001 + 0.08294624912216243 + 3 + + + 1.0779623198512718 + 0.055174528323052245 + 0.31850000000000017 + 3.6000000000000014 + 0.12585502713057742 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.6710617050853205 + 0.1001189160557567 + 0.11375000000000005 + 4.999999999999998 + 0.11878637758417326 + 5 + + + + 0.21499461697210479 + 0.0011126847886580823 + 0.20475000000000002 + 2.5999999999999996 + 0.02022815907456897 + 1 + + + 0.48989603967310597 + 0.008310479300556561 + 0.18200000000000002 + 3.1999999999999993 + 0.043377926879407946 + 2 + + + 0.8244742843912946 + 0.02498853442633807 + 0.15925000000000003 + 3.799999999999999 + 0.06828656297195088 + 3 + + + 1.2183586607758967 + 0.05454800808369409 + 0.13650000000000004 + 4.399999999999999 + 0.09380321820260577 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.6689588350175424 + 0.12103458682942048 + 0.2275 + 4.999999999999998 + 0.16206748709157984 + 5 + + + + 0.21499461697210479 + 0.0011126847886580823 + 0.2275 + 2.5999999999999996 + 0.020802692372949058 + 1 + + + 0.4898857101858334 + 0.008656195240332353 + 0.2275 + 3.1999999999999993 + 0.04741078726858157 + 2 + + + 0.8243599390234975 + 0.027237901182910397 + 0.2275 + 3.799999999999999 + 0.07982428468689753 + 3 + + + 1.2177671282853366 + 0.0624887187952375 + 0.2275 + 4.399999999999999 + 0.11804318462789695 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.6662983832175198 + 0.1424446340437208 + 0.3412500000000002 + 4.999999999999998 + 0.2069100357176274 + 5 + + + + 0.21499461697210479 + 0.0011126847886580823 + 0.25025000000000003 + 2.5999999999999996 + 0.021380259746057957 + 1 + + + 0.48987473680943483 + 0.009004715984581335 + 0.2730000000000001 + 3.1999999999999993 + 0.05149486070446035 + 2 + + + 0.824231398515678 + 0.029518308680771505 + 0.2957500000000001 + 3.799999999999999 + 0.09159654058116067 + 3 + + + 1.2170621662662622 + 0.07058153132808218 + 0.31850000000000017 + 4.399999999999999 + 0.14296494715991054 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.8944014683492822 + 0.1272994278783968 + 0.11375000000000005 + 6.000000000000001 + 0.13353397538774925 + 5 + + + + 0.2199943829274137 + 0.0011610623881649557 + 0.20475000000000002 + 2.8 + 0.020686962909500707 + 1 + + + 0.5198781709808863 + 0.009310090199096382 + 0.18200000000000002 + 3.5999999999999996 + 0.04593225939007839 + 2 + + + 0.8993310995734252 + 0.02952331612614556 + 0.15925000000000003 + 4.3999999999999995 + 0.07417951071195776 + 3 + + + 1.3577773256783519 + 0.0671470215246117 + 0.13650000000000004 + 5.2 + 0.10388894714009002 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.8912573607996037 + 0.1552160137680472 + 0.2275 + 6.000000000000001 + 0.1838377465516428 + 5 + + + + 0.2199943829274137 + 0.0011610623881649557 + 0.2275 + 2.8 + 0.02128647591650601 + 1 + + + 0.5198656121830639 + 0.009713003468488223 + 0.2275 + 3.5999999999999996 + 0.050313488529923296 + 2 + + + 0.8991792741609113 + 0.03230119592985066 + 0.2275 + 4.3999999999999995 + 0.08708103784025185 + 3 + + + 1.3569378157544723 + 0.07739214933837968 + 0.2275 + 5.2 + 0.1315891238474917 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 1.8872522481311909 + 0.18377860382993996 + 0.3412500000000002 + 6.000000000000001 + 0.23597155582352033 + 5 + + + + 0.2199943829274137 + 0.0011610623881649557 + 0.25025000000000003 + 2.8 + 0.02188915491453269 + 1 + + + 0.5198522512904522 + 0.010119205836841904 + 0.2730000000000001 + 3.5999999999999996 + 0.0547506826555607 + 2 + + + 0.8990080269477116 + 0.03511772896538641 + 0.2957500000000001 + 4.3999999999999995 + 0.10024683204015891 + 3 + + + 1.3559320896739986 + 0.08783361038392228 + 0.31850000000000017 + 5.2 + 0.16007486718924369 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 2.1148635461249663 + 0.1573117401518895 + 0.11375000000000005 + 6.876717391979616 + 0.1481498037872205 + 5 + + + + 0.22499414888272262 + 0.0012094399876718287 + 0.20475000000000002 + 3.0 + 0.021145766744432436 + 1 + + + 0.5498584948113786 + 0.010358644916906787 + 0.18200000000000002 + 4.0 + 0.04848659190074882 + 2 + + + 0.9741646736223161 + 0.03441312004344979 + 0.15925000000000003 + 5.0 + 0.08007245845196463 + 3 + + + 1.4970748179575644 + 0.08100303700175751 + 0.13650000000000004 + 5.997113636363636 + 0.11397467607757426 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.2275 + 2.0 + 0.0 + 0 + + + 2.1104009460453805 + 0.1931151358411401 + 0.2275 + 6.876717391979616 + 0.2053667629527207 + 5 + + + + 0.22499414888272262 + 0.0012094399876718287 + 0.2275 + 3.0 + 0.021770259460062967 + 1 + + + 0.5498434223391124 + 0.010822986833131074 + 0.2275 + 4.0 + 0.05321618979126504 + 2 + + + 0.9739681225692731 + 0.03777456992784417 + 0.2275 + 5.0 + 0.0943377909936062 + 3 + + + 1.4959270671142952 + 0.09384270192579545 + 0.2275 + 5.997113636363636 + 0.14513506306708646 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.5495430845862127 + 0.01850252899015523 + 0.2274999999999998 + 2.7755575615628914e-16 + 0.07296597420821735 + 5 + + + + 0.18999008611098198 + 0.0013358150089185028 + 0.31849999999999995 + 1.6 + 0.02772165941263737 + 1 + + + 0.3399068108348221 + 0.006264814534963333 + 0.2957499999999999 + 1.2000000000000002 + 0.048024946489710243 + 2 + + + 0.4497601863743528 + 0.01192703620428683 + 0.27299999999999985 + 0.8000000000000003 + 0.06177354366318666 + 3 + + + 0.5196176729311698 + 0.016388569606137257 + 0.2502499999999998 + 0.4000000000000003 + 0.06981159863545504 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.5494774308916672 + 0.019582245684574156 + 0.34125 + 2.7755575615628914e-16 + 0.0816361369803732 + 5 + + + + 0.18999008611098198 + 0.0013358150089185028 + 0.34125 + 1.6 + 0.028201574593219828 + 1 + + + 0.3399020698073943 + 0.0063962055872022715 + 0.34125 + 1.2000000000000002 + 0.05046597558786706 + 2 + + + 0.44973758238879225 + 0.012389722071654709 + 0.34125 + 0.8000000000000003 + 0.0667932029839417 + 3 + + + 0.5195690782719591 + 0.017239452250449275 + 0.34125 + 0.4000000000000003 + 0.07718325678144375 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.5494045531563 + 0.0206904205856447 + 0.45500000000000024 + 2.7755575615628914e-16 + 0.09066460579912661 + 5 + + + + 0.18999008611098198 + 0.0013358150089185028 + 0.36400000000000005 + 1.6 + 0.028685383156295853 + 1 + + + 0.3398971263287401 + 0.006529143292840979 + 0.3867500000000001 + 1.2000000000000002 + 0.0529520215290427 + 2 + + + 0.4497133171885169 + 0.01286091491850792 + 0.40950000000000014 + 0.8000000000000003 + 0.07195368074465401 + 3 + + + 0.5195157516176993 + 0.01811038796032806 + 0.4322500000000002 + 0.4000000000000003 + 0.0848221583206377 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.773777630327999 + 0.036778961375849156 + 0.2274999999999998 + 0.9999999999999992 + 0.0989293563667291 + 5 + + + + 0.19498953533936986 + 0.0014100269538584195 + 0.31849999999999995 + 1.7999999999999998 + 0.02843714415798214 + 1 + + + 0.36988227256975903 + 0.0074394327563857025 + 0.2957499999999999 + 1.5999999999999996 + 0.05210680750720333 + 2 + + + 0.5246282187616694 + 0.016275125201812853 + 0.27299999999999985 + 1.3999999999999995 + 0.07145629580066619 + 3 + + + 0.6592435217504904 + 0.02644443707985516 + 0.2502499999999998 + 1.1999999999999993 + 0.08692175380606852 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.7735207453558987 + 0.03992362264709838 + 0.34125 + 0.9999999999999992 + 0.11503273847234396 + 5 + + + + 0.19498953533936986 + 0.0014100269538584195 + 0.34125 + 1.7999999999999998 + 0.0289437212930414 + 1 + + + 0.3698757977392662 + 0.007609226621136432 + 0.34125 + 1.5999999999999996 + 0.05491885578679649 + 2 + + + 0.5245879470703102 + 0.017006293109198708 + 0.34125 + 1.3999999999999995 + 0.07792540348126528 + 3 + + + 0.6591221987652455 + 0.028188597798350444 + 0.34125 + 1.1999999999999993 + 0.09796336437644777 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.7732256452240094 + 0.04317171874423119 + 0.45500000000000024 + 0.9999999999999992 + 0.13193508435435297 + 5 + + + + 0.19498953533936986 + 0.0014100269538584195 + 0.36400000000000005 + 1.7999999999999998 + 0.029454408109621653 + 1 + + + 0.36986903400760074 + 0.007781053715279214 + 0.3867500000000001 + 1.5999999999999996 + 0.057783713003605366 + 2 + + + 0.5245444173285561 + 0.01775167521704194 + 0.40950000000000014 + 1.3999999999999995 + 0.08458409025985072 + 3 + + + 0.6589868281480493 + 0.029978879661788894 + 0.4322500000000002 + 1.1999999999999993 + 0.10944242539647282 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.9975015474519983 + 0.060400372680034065 + 0.2274999999999998 + 2.0 + 0.12489273852524088 + 5 + + + + 0.19998898456775774 + 0.0014842388987983365 + 0.31849999999999995 + 2.0 + 0.029152628903326913 + 1 + + + 0.3998543448655045 + 0.008691092272808579 + 0.2957499999999999 + 2.0 + 0.056188668524696436 + 2 + + + 0.5994591048523997 + 0.021193821811184475 + 0.27299999999999985 + 2.0 + 0.08113904793814573 + 3 + + + 0.7986994449282936 + 0.03856959637934665 + 0.2502499999999998 + 2.0 + 0.10403190897668202 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.9968636436712537 + 0.06668291007147922 + 0.34125 + 2.0 + 0.14842933996431493 + 5 + + + + 0.19998898456775774 + 0.0014842388987983365 + 0.34125 + 2.0 + 0.029685867992862977 + 1 + + + 0.39984580093563826 + 0.008903798511526782 + 0.34125 + 2.0 + 0.059371735985725954 + 2 + + + 0.5993943380663633 + 0.022252140825805816 + 0.34125 + 2.0 + 0.08905760397858895 + 3 + + + 0.7984587565740161 + 0.04151750346868447 + 0.34125 + 2.0 + 0.11874347197145194 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 0.996116484251118 + 0.07318837215945928 + 0.45500000000000024 + 2.0 + 0.17320556290957945 + 5 + + + + 0.19998898456775774 + 0.0014842388987983365 + 0.36400000000000005 + 2.0 + 0.030223433062947447 + 1 + + + 0.3998368613980419 + 0.009119086194963388 + 0.3867500000000001 + 2.0 + 0.06261540447816803 + 2 + + + 0.5993239597784898 + 0.02333177298912749 + 0.40950000000000014 + 2.0 + 0.09721449977504744 + 3 + + + 0.7981872010054409 + 0.044547821425006025 + 0.4322500000000002 + 2.0 + 0.13406269247230798 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.22058749912575 + 0.08935305812956286 + 0.2274999999999998 + 3.000000000000001 + 0.15085612068375268 + 5 + + + + 0.20498843379614562 + 0.0015584508437382532 + 0.31849999999999995 + 2.2 + 0.029868113648671687 + 1 + + + 0.4298228153488825 + 0.010019783500358584 + 0.2957499999999999 + 2.4000000000000004 + 0.06027052954218953 + 2 + + + 0.6742483477180286 + 0.026682814749506772 + 0.27299999999999985 + 2.6000000000000005 + 0.09082180007562526 + 3 + + + 0.9379543462788682 + 0.05276125311143949 + 0.2502499999999998 + 2.8000000000000007 + 0.12114206414729552 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.2193172127106755 + 0.09983654907765317 + 0.34125 + 3.000000000000001 + 0.18182594145628575 + 5 + + + + 0.20498843379614562 + 0.0015584508437382532 + 0.34125 + 2.2 + 0.030428014692684552 + 1 + + + 0.4298118400694356 + 0.010279910033813944 + 0.34125 + 2.4000000000000004 + 0.0638246161846554 + 2 + + + 0.6741512107286263 + 0.028126851440766366 + 0.34125 + 2.6000000000000005 + 0.10018980447591255 + 3 + + + 0.9375367476384127 + 0.0572219504312724 + 0.34125 + 2.8000000000000007 + 0.139523579566456 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.217810543139256 + 0.11070233575642884 + 0.45500000000000024 + 3.000000000000001 + 0.21447604146480592 + 5 + + + + 0.20498843379614562 + 0.0015584508437382532 + 0.36400000000000005 + 2.2 + 0.03099245801627325 + 1 + + + 0.42980034017125673 + 0.010543227664579874 + 0.3867500000000001 + 2.4000000000000004 + 0.06744709595273071 + 2 + + + 0.6740452096373266 + 0.029600668208455944 + 0.40950000000000014 + 2.6000000000000005 + 0.10984490929024418 + 3 + + + 0.9370618062878806 + 0.06181107619648347 + 0.4322500000000002 + 2.8000000000000007 + 0.15868295954814315 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.4429085075407857 + 0.12362030761823642 + 0.2274999999999998 + 4.000000000000002 + 0.1768195028422645 + 5 + + + + 0.20998788302453353 + 0.00163266278867817 + 0.31849999999999995 + 2.4000000000000004 + 0.03058359839401646 + 1 + + + 0.4597874716727195 + 0.01142549629055788 + 0.2957499999999999 + 2.8000000000000007 + 0.06435239055968264 + 2 + + + 0.7489914529877486 + 0.03274175769542435 + 0.27299999999999985 + 3.200000000000001 + 0.10050455221310482 + 3 + + + 1.0769771747012276 + 0.06901614951001189 + 0.2502499999999998 + 3.6000000000000014 + 0.13825221931790904 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.440693316453971 + 0.13935542303975793 + 0.34125 + 4.000000000000002 + 0.21522254294825666 + 5 + + + + 0.20998788302453353 + 0.00163266278867817 + 0.34125 + 2.4000000000000004 + 0.031170161392506127 + 1 + + + 0.4597736758460308 + 0.011737549285670253 + 0.34125 + 2.8000000000000007 + 0.06827749638358485 + 2 + + + 0.7488530242328859 + 0.03462996270651619 + 0.34125 + 3.200000000000001 + 0.11132200497323619 + 3 + + + 1.076314248805756 + 0.07529698016585115 + 0.34125 + 3.6000000000000014 + 0.16030368716146012 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.4380428246522345 + 0.15566608331881077 + 0.45500000000000024 + 4.000000000000002 + 0.2557465200200324 + 5 + + + + 0.20998788302453353 + 0.00163266278867817 + 0.36400000000000005 + 2.4000000000000004 + 0.03176148296959905 + 1 + + + 0.45975920203856857 + 0.012053464249675155 + 0.3867500000000001 + 2.8000000000000007 + 0.07227878742729338 + 2 + + + 0.7487014375659576 + 0.03655775538911506 + 0.40950000000000014 + 3.200000000000001 + 0.12247531880544091 + 3 + + + 1.0755557173594927 + 0.08176138147961613 + 0.4322500000000002 + 3.6000000000000014 + 0.1833032266239783 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.6643380243754906 + 0.16318241495044394 + 0.2274999999999998 + 4.999999999999998 + 0.20278288500077613 + 5 + + + + 0.2149873322529214 + 0.0017068747336180868 + 0.31849999999999995 + 2.5999999999999996 + 0.03129908313936122 + 1 + + + 0.48974810151729586 + 0.012908219930392234 + 0.2957499999999999 + 3.1999999999999993 + 0.0684342515771757 + 2 + + + 0.8236839291182144 + 0.03937026930978321 + 0.27299999999999985 + 3.799999999999999 + 0.1101873043505843 + 3 + + + 1.215736931032728 + 0.08733056515271018 + 0.2502499999999998 + 4.399999999999999 + 0.15536237448852244 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.6608047590038992 + 0.1852048828106777 + 0.34125 + 4.999999999999998 + 0.24861914444022737 + 5 + + + + 0.2149873322529214 + 0.0017068747336180868 + 0.34125 + 2.5999999999999996 + 0.0319123080923277 + 1 + + + 0.4897310690050991 + 0.01327670368709019 + 0.34125 + 3.1999999999999993 + 0.07273037658251429 + 2 + + + 0.8234942419979727 + 0.04176096394338352 + 0.34125 + 3.799999999999999 + 0.12245420547055977 + 3 + + + 1.2147494307883968 + 0.09573689599211142 + 0.34125 + 4.399999999999999 + 0.18108379475646413 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.6565501984345028 + 0.20802266804371145 + 0.45500000000000024 + 4.999999999999998 + 0.29701699857525865 + 5 + + + + 0.2149873322529214 + 0.0017068747336180868 + 0.36400000000000005 + 2.5999999999999996 + 0.03253050792292484 + 1 + + + 0.4897131787537763 + 0.013649781268774596 + 0.3867500000000001 + 3.1999999999999993 + 0.07711047890185603 + 2 + + + 0.8232859204166016 + 0.04420236364189789 + 0.40950000000000014 + 3.799999999999999 + 0.13510572832063758 + 3 + + + 1.213614167767194 + 0.10439035236299234 + 0.4322500000000002 + 4.399999999999999 + 0.20792349369981336 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.884750001023224 + 0.20801668872827567 + 0.2274999999999998 + 6.000000000000001 + 0.22874626715928795 + 5 + + + + 0.2199867814813093 + 0.0017810866785580037 + 0.31849999999999995 + 2.8 + 0.032014567884706 + 1 + + + 0.5197044925917991 + 0.01446794314238275 + 0.2957499999999999 + 3.5999999999999996 + 0.07251611259466881 + 2 + + + 0.898321287663135 + 0.04656793325834549 + 0.27299999999999985 + 4.3999999999999995 + 0.11987005648806384 + 3 + + + 1.3542026748914395 + 0.10770031777835978 + 0.2502499999999998 + 5.2 + 0.17247252965913595 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.8794654467946281 + 0.2373447767105923 + 0.34125 + 6.000000000000001 + 0.28201574593219825 + 5 + + + + 0.2199867814813093 + 0.0017810866785580037 + 0.34125 + 2.8 + 0.032654454792149276 + 1 + + + 0.5196837803224755 + 0.014897359980485768 + 0.34125 + 3.5999999999999996 + 0.07718325678144373 + 2 + + + 0.8980693321043836 + 0.049519296077914624 + 0.34125 + 4.3999999999999995 + 0.13358640596788338 + 3 + + + 1.3528005710929976 + 0.11853526482537702 + 0.34125 + 5.2 + 0.2018639023514682 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 1.8730717356663709 + 0.267705795042026 + 0.45500000000000024 + 6.000000000000001 + 0.3382874771304851 + 5 + + + + 0.2199867814813093 + 0.0017810866785580037 + 0.36400000000000005 + 2.8 + 0.033299532876250634 + 1 + + + 0.5196620021155012 + 0.015332163233507817 + 0.3867500000000001 + 3.5999999999999996 + 0.0819421703764187 + 2 + + + 0.8977919418616931 + 0.05253375673659212 + 0.40950000000000014 + 4.3999999999999995 + 0.1477361378358343 + 3 + + + 1.351182574091435 + 0.12968848501271873 + 0.4322500000000002 + 5.2 + 0.2325437607756485 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.34125 + 2.0 + 0.0 + 0 + + + 2.1015867980384746 + 0.25754905983602544 + 0.2274999999999998 + 6.876717391979616 + 0.25445515527918317 + 5 + + + + 0.22498623070969717 + 0.0018552986234979204 + 0.31849999999999995 + 3.0 + 0.03273005263005077 + 1 + + + 0.5496564326357746 + 0.01610465408466113 + 0.2957499999999999 + 4.0 + 0.07659797361216192 + 2 + + + 0.9728990435426841 + 0.054334298236555195 + 0.27299999999999985 + 5.0 + 0.1295528086255434 + 3 + + + 1.4923435315057876 + 0.13012076420489313 + 0.2502499999999998 + 5.997113636363636 + 0.18958268482974944 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.5491083559907971 + 0.02578268475269574 + 0.3412499999999998 + 2.7755575615628914e-16 + 0.10298818610068211 + 5 + + + + 0.18998118664268343 + 0.001840122380325224 + 0.43224999999999997 + 1.6 + 0.03832236847091787 + 1 + + + 0.3398213656593887 + 0.00866568596055649 + 0.4094999999999999 + 1.2000000000000002 + 0.06684324846945552 + 2 + + + 0.44953641240106296 + 0.01655575122438747 + 0.38674999999999987 + 0.8000000000000003 + 0.08651635688287035 + 3 + + + 0.5192562561638501 + 0.0228077716961012 + 0.3639999999999998 + 0.4000000000000003 + 0.09826561942984563 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.5490086004691852 + 0.026963088398987537 + 0.455 + 2.7755575615628914e-16 + 0.1124597594462612 + 5 + + + + 0.18998118664268343 + 0.001840122380325224 + 0.455 + 1.6 + 0.038849735081435674 + 1 + + + 0.33981417379804296 + 0.008809882915404979 + 0.455 + 1.2000000000000002 + 0.06952057856677964 + 2 + + + 0.44950209639646943 + 0.017062646416064104 + 0.455 + 0.8000000000000003 + 0.09201253045603187 + 3 + + + 0.5191824408133605 + 0.02373867287419295 + 0.455 + 0.4000000000000003 + 0.1063255907491924 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.5488984030490971 + 0.02818650223413094 + 0.5687500000000002 + 2.7755575615628914e-16 + 0.12247486937313834 + 5 + + + + 0.18998118664268343 + 0.001840122380325224 + 0.47775 + 1.6 + 0.03938300445807191 + 1 + + + 0.3398066854915879 + 0.008956422449057488 + 0.5005000000000001 + 1.2000000000000002 + 0.07226616457850094 + 2 + + + 0.4494653738178726 + 0.017582413864101948 + 0.5232500000000001 + 0.8000000000000003 + 0.0977222478341477 + 3 + + + 0.5191017858335181 + 0.024699893082885782 + 0.5460000000000002 + 0.4000000000000003 + 0.11479089638146318 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.7725851245826697 + 0.05151853889451555 + 0.3412499999999998 + 0.9999999999999992 + 0.14089902200202958 + 5 + + + + 0.19498014145616582 + 0.0019423514014544029 + 0.43224999999999997 + 1.7999999999999998 + 0.03931543177540056 + 1 + + + 0.36977414743048265 + 0.010294105519179399 + 0.4094999999999999 + 1.5999999999999996 + 0.07257067146308074 + 2 + + + 0.5242793812209281 + 0.02261762519231074 + 0.38674999999999987 + 1.3999999999999995 + 0.10026631431639745 + 3 + + + 0.6585192385307671 + 0.036900999791827 + 0.3639999999999998 + 1.1999999999999993 + 0.1228861972228912 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.7721943523248227 + 0.05494707962633018 + 0.455 + 0.9999999999999992 + 0.15846602467427706 + 5 + + + + 0.19498014145616582 + 0.0019423514014544029 + 0.455 + 1.7999999999999998 + 0.03987209653094714 + 1 + + + 0.36976432449314284 + 0.010480427510551506 + 0.455 + 1.5999999999999996 + 0.07565474726384842 + 2 + + + 0.524218225506734 + 0.023418241663506954 + 0.455 + 1.3999999999999995 + 0.10734795219870383 + 3 + + + 0.6583348347606945 + 0.03880664665952951 + 0.455 + 1.1999999999999993 + 0.13495171133551337 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.7717488935154574 + 0.058531469206499646 + 0.5687500000000002 + 0.9999999999999992 + 0.17724522537106244 + 5 + + + + 0.19498014145616582 + 0.0019423514014544029 + 0.47775 + 1.7999999999999998 + 0.04043499198406317 + 1 + + + 0.3697540803554604 + 0.010669828636591333 + 0.5005000000000001 + 1.5999999999999996 + 0.07881889374606552 + 2 + + + 0.5241523780511328 + 0.02424035284236739 + 0.5232500000000001 + 1.3999999999999995 + 0.11471708030728733 + 3 + + + 0.6581302892549603 + 0.04078191575952908 + 0.5460000000000002 + 1.1999999999999993 + 0.14768074791113203 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.9950243191164474 + 0.08489125873393591 + 0.3412499999999998 + 2.0 + 0.17880985790337714 + 5 + + + + 0.19997909626964824 + 0.002044580422583582 + 0.43224999999999997 + 2.0 + 0.04030849507988326 + 1 + + + 0.3997203720655301 + 0.012029822330201109 + 0.4094999999999999 + 2.0 + 0.07829809445670599 + 2 + + + 0.598949342134961 + 0.02948052167423687 + 0.38674999999999987 + 2.0 + 0.11401627174992458 + 3 + + + 0.797442748390409 + 0.053923732577659936 + 0.3639999999999998 + 2.0 + 0.14750677501593681 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.994053386796287 + 0.09172436926739985 + 0.455 + 2.0 + 0.20447228990229302 + 5 + + + + 0.19997909626964824 + 0.002044580422583582 + 0.455 + 2.0 + 0.040894457980458605 + 1 + + + 0.39970740894665346 + 0.012263208957082678 + 0.455 + 2.0 + 0.08178891596091721 + 2 + + + 0.5988509675974587 + 0.030638798793138335 + 0.455 + 2.0 + 0.12268337394137581 + 3 + + + 0.7970767795695387 + 0.05714062367255432 + 0.455 + 2.0 + 0.16357783192183442 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 0.9929273664072162 + 0.09889198995274671 + 0.5687500000000002 + 2.0 + 0.2320155813689866 + 5 + + + + 0.19997909626964824 + 0.002044580422583582 + 0.47775 + 2.0 + 0.04148697951005443 + 1 + + + 0.39969387121530764 + 0.012500504378090404 + 0.5005000000000001 + 2.0 + 0.08537162291363011 + 2 + + + 0.5987445507712806 + 0.03182928296956495 + 0.5232500000000001 + 2.0 + 0.131711912780427 + 3 + + + 0.7966668270290519 + 0.0604816775704808 + 0.5460000000000002 + 2.0 + 0.18057059944080092 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.2161633801974694 + 0.12586049070563152 + 0.3412499999999998 + 3.000000000000001 + 0.21672069380472472 + 5 + + + + 0.20497805108313066 + 0.0021468094437127614 + 0.43224999999999997 + 2.2 + 0.04130155838436596 + 1 + + + 0.42965962678002967 + 0.013872810511467028 + 0.4094999999999999 + 2.4000000000000004 + 0.08402551745033121 + 2 + + + 0.6735373909911136 + 0.037143576760348296 + 0.38674999999999987 + 2.6000000000000005 + 0.1277662291834517 + 3 + + + 0.935963999723686 + 0.07386798931480548 + 0.3639999999999998 + 2.8000000000000007 + 0.17212735280898245 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.2142297278477472 + 0.13723351747666795 + 0.455 + 3.000000000000001 + 0.250478555130309 + 5 + + + + 0.20497805108313066 + 0.0021468094437127614 + 0.455 + 2.2 + 0.04191681942997007 + 1 + + + 0.4296429734334954 + 0.014158197921019081 + 0.455 + 2.4000000000000004 + 0.08792308465798601 + 2 + + + 0.6733898269150329 + 0.03872323699637438 + 0.455 + 2.6000000000000005 + 0.1380187956840478 + 3 + + + 0.9353289266706881 + 0.07872959191010694 + 0.455 + 2.8000000000000007 + 0.19220395250815547 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.2119627017341605 + 0.14917717697384358 + 0.5687500000000002 + 3.000000000000001 + 0.2867859373669108 + 5 + + + + 0.20497805108313066 + 0.0021468094437127614 + 0.47775 + 2.2 + 0.04253896703604569 + 1 + + + 0.42962556058388623 + 0.014448416521102656 + 0.5005000000000001 + 2.4000000000000004 + 0.09192435208119472 + 2 + + + 0.6732296086677725 + 0.04034786351575933 + 0.5232500000000001 + 2.6000000000000005 + 0.1487067452535667 + 3 + + + 0.9346125480017275 + 0.08378424222123498 + 0.5460000000000002 + 2.8000000000000007 + 0.21346045097046987 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.4357412822816125 + 0.17437691941172048 + 0.3412499999999998 + 4.000000000000002 + 0.2546315297060723 + 5 + + + + 0.20997700589661306 + 0.0022490384648419406 + 0.43224999999999997 + 2.4000000000000004 + 0.042294621688848656 + 1 + + + 0.45959149888750084 + 0.015823042649072454 + 0.4094999999999999 + 2.8000000000000007 + 0.08975294044395646 + 2 + + + 0.7480346336650407 + 0.04560582860599813 + 0.38674999999999987 + 3.200000000000001 + 0.14151618661697885 + 3 + + + 1.0740203907459118 + 0.0967244529722695 + 0.3639999999999998 + 3.6000000000000014 + 0.19674793060202808 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.4323701895819239 + 0.1913986835904468 + 0.455 + 4.000000000000002 + 0.29648482035832496 + 5 + + + + 0.20997700589661306 + 0.0022490384648419406 + 0.455 + 2.4000000000000004 + 0.04293918087948154 + 1 + + + 0.4595705643454018 + 0.016165363298355225 + 0.455 + 2.8000000000000007 + 0.0940572533550548 + 2 + + + 0.7478243214647041 + 0.04767034911542388 + 0.455 + 3.200000000000001 + 0.15335421742671979 + 3 + + + 1.0730122183345856 + 0.10356061607249242 + 0.455 + 3.6000000000000014 + 0.22083007309447653 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.428388635158191 + 0.20927388132748798 + 0.5687500000000002 + 4.000000000000002 + 0.341556293364835 + 5 + + + + 0.20997700589661306 + 0.0022490384648419406 + 0.47775 + 2.4000000000000004 + 0.043590954562036946 + 1 + + + 0.45954865111256693 + 0.016513529875779663 + 0.5005000000000001 + 2.8000000000000007 + 0.09847708124875931 + 2 + + + 0.7475952870653646 + 0.049794592603153526 + 0.5232500000000001 + 3.200000000000001 + 0.16570157772670638 + 3 + + + 1.0718690482586997 + 0.11067196821110342 + 0.5460000000000002 + 3.6000000000000014 + 0.24635030250013878 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.6534988378076736 + 0.23038232494348573 + 0.3412499999999998 + 4.999999999999998 + 0.29254236560741975 + 5 + + + + 0.21497596071009548 + 0.0023512674859711194 + 0.43224999999999997 + 2.5999999999999996 + 0.043287684993331355 + 1 + + + 0.4895155758049833 + 0.017880489797720694 + 0.4094999999999999 + 3.1999999999999993 + 0.09548036343758166 + 2 + + + 0.8224321871246358 + 0.05486621754614745 + 0.38674999999999987 + 3.799999999999999 + 0.1552661440505059 + 3 + + + 1.2115495321513192 + 0.12248247441841249 + 0.3639999999999998 + 4.399999999999999 + 0.2213685083950736 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.648124956968856 + 0.2541297508060354 + 0.455 + 4.999999999999998 + 0.3424910855863407 + 5 + + + + 0.21497596071009548 + 0.0023512674859711194 + 0.455 + 2.5999999999999996 + 0.043961542328993 + 1 + + + 0.4894897281975947 + 0.018284672215508065 + 0.455 + 3.1999999999999993 + 0.10019142205212359 + 2 + + + 0.8221439845146143 + 0.05747880181549142 + 0.455 + 3.799999999999999 + 0.16868963916939173 + 3 + + + 1.2100479340435226 + 0.13161884513798452 + 0.455 + 4.399999999999999 + 0.24945619368079744 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.641744808513407 + 0.27904694796002044 + 0.5687500000000002 + 4.999999999999998 + 0.3963266493627589 + 5 + + + + 0.21497596071009548 + 0.0023512674859711194 + 0.47775 + 2.5999999999999996 + 0.0446429420880282 + 1 + + + 0.48946264559939845 + 0.018695807215435144 + 0.5005000000000001 + 3.1999999999999993 + 0.10502981041632388 + 2 + + + 0.821829342015546 + 0.060167807460713076 + 0.5232500000000001 + 3.799999999999999 + 0.18269641019984598 + 3 + + + 1.2083384448591488 + 0.14112452204180798 + 0.5460000000000002 + 4.399999999999999 + 0.2792401540298075 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.8691789992166647 + 0.2938096504738631 + 0.3412499999999998 + 6.000000000000001 + 0.3304532015087673 + 5 + + + + 0.21997491552357787 + 0.0024534965071002987 + 0.43224999999999997 + 2.8 + 0.044280748297814046 + 1 + + + 0.5194314450585337 + 0.020045121481100395 + 0.4094999999999999 + 3.5999999999999996 + 0.1012077864312069 + 2 + + + 0.8967211804932822 + 0.06492358622123967 + 0.38674999999999987 + 4.3999999999999995 + 0.16901610148403304 + 3 + + + 1.3484892752634017 + 0.1511300772056025 + 0.3639999999999998 + 5.2 + 0.2459890861881192 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.8611481610793983 + 0.3253224741896736 + 0.455 + 6.000000000000001 + 0.3884973508143567 + 5 + + + + 0.21997491552357787 + 0.0024534965071002987 + 0.455 + 2.8 + 0.04498390377850446 + 1 + + + 0.5194000116354601 + 0.02051609002978997 + 0.455 + 3.5999999999999996 + 0.10632559074919237 + 2 + + + 0.896338366097716 + 0.06814713577467402 + 0.455 + 4.3999999999999995 + 0.18402506091206372 + 3 + + + 1.3463577366690636 + 0.16288752104867624 + 0.455 + 5.2 + 0.2780823142671185 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.455 + 2.0 + 0.0 + 0 + + + 1.8515778070876656 + 0.3583395204538188 + 0.5687500000000002 + 6.000000000000001 + 0.45109700536068315 + 5 + + + + 0.21997491552357787 + 0.0024534965071002987 + 0.47775 + 2.8 + 0.045694929614019456 + 1 + + + 0.5193670469971688 + 0.02099520927713444 + 0.5005000000000001 + 3.5999999999999996 + 0.11158253958388846 + 2 + + + 0.895919552384548 + 0.07146568470561032 + 0.5232500000000001 + 4.3999999999999995 + 0.19969124267298563 + 3 + + + 1.3439234491843486 + 0.17511889342429654 + 0.5460000000000002 + 5.2 + 0.31213000555947645 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.5484561223475788 + 0.03387234074252107 + 0.45499999999999974 + 2.7755575615628914e-16 + 0.1362557934853649 + 5 + + + + 0.18996788560900513 + 0.00240407134772878 + 0.5459999999999999 + 1.6 + 0.050160292035174456 + 1 + + + 0.3396934956788012 + 0.011344455646063418 + 0.5232499999999999 + 1.2000000000000002 + 0.08779987324386579 + 2 + + + 0.44920114843688486 + 0.021710080602468835 + 0.5004999999999998 + 0.8000000000000003 + 0.11400658186124255 + 3 + + + 0.5187142771477645 + 0.02994565026428725 + 0.4777499999999998 + 0.4000000000000003 + 0.12982399895753033 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.5483083644314194 + 0.03520314028510121 + 0.56875 + 2.7755575615628914e-16 + 0.14693294819234184 + 5 + + + + 0.18996788560900513 + 0.00240407134772878 + 0.56875 + 1.6 + 0.05075865483008171 + 1 + + + 0.3396828296045159 + 0.01150779348909622 + 0.56875 + 1.2000000000000002 + 0.09083127706435676 + 2 + + + 0.4491502834248403 + 0.022283032668483728 + 0.56875 + 0.8000000000000003 + 0.12021786670282512 + 3 + + + 0.5186049140378661 + 0.030996083693293774 + 0.56875 + 0.4000000000000003 + 0.13891842374548682 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.5481445134958789 + 0.03659750855082011 + 0.6825000000000002 + 2.7755575615628914e-16 + 0.1584179269916447 + 5 + + + + 0.18996788560900513 + 0.00240407134772878 + 0.5915 + 1.6 + 0.051365783095923746 + 1 + + + 0.3396717015944021 + 0.0116746048904788 + 0.6142500000000001 + 1.2000000000000002 + 0.09396405215923614 + 2 + + + 0.44909570196615095 + 0.022875043833200236 + 0.6370000000000001 + 0.8000000000000003 + 0.12674636719806748 + 3 + + + 0.5184850095980301 + 0.03209135496212861 + 0.6597500000000002 + 0.4000000000000003 + 0.14861512951895048 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.7707930058703286 + 0.06784021307877365 + 0.45499999999999974 + 0.9999999999999992 + 0.18726961367681935 + 5 + + + + 0.19496610147617208 + 0.0025376308670470456 + 0.5459999999999999 + 1.7999999999999998 + 0.05146280373215545 + 1 + + + 0.3696123218859388 + 0.013478462172735257 + 0.5232499999999999 + 1.5999999999999996 + 0.0953540989149545 + 2 + + + 0.5237565824366486 + 0.02967459652726811 + 0.5004999999999998 + 1.3999999999999995 + 0.13225311929181632 + 3 + + + 0.657432268376401 + 0.04850664328395532 + 0.4777499999999998 + 1.1999999999999993 + 0.16271429246335936 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.7702145844165893 + 0.07169165593061587 + 0.56875 + 0.9999999999999992 + 0.20704188154375433 + 5 + + + + 0.19496610147617208 + 0.0025376308670470456 + 0.56875 + 1.7999999999999998 + 0.05209440890455755 + 1 + + + 0.3695977536778092 + 0.013689484870508679 + 0.56875 + 1.5999999999999996 + 0.09884580151121175 + 2 + + + 0.52366594190764 + 0.03057891614778086 + 0.56875 + 1.3999999999999995 + 0.1402541778199626 + 3 + + + 0.6571591393869562 + 0.050653155581084006 + 0.56875 + 1.1999999999999993 + 0.17631953783081014 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.7695526339192582 + 0.0757723815141736 + 0.6825000000000002 + 0.9999999999999992 + 0.22861620909301952 + 5 + + + + 0.19496610147617208 + 0.0025376308670470456 + 0.5915 + 1.7999999999999998 + 0.05273526651850191 + 1 + + + 0.3695825314884118 + 0.013905072358789631 + 0.6142500000000001 + 1.5999999999999996 + 0.10245642260197382 + 2 + + + 0.5235680930868714 + 0.031515031842883 + 0.6370000000000001 + 1.3999999999999995 + 0.14868230576351046 + 3 + + + 0.6568551864988249 + 0.05290238507397434 + 0.6597500000000002 + 1.1999999999999993 + 0.19091077179193847 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.9912984829581846 + 0.11192602175560543 + 0.45499999999999974 + 2.0 + 0.23828343386827386 + 5 + + + + 0.19996431734333903 + 0.002671190386365311 + 0.5459999999999999 + 2.0 + 0.05276531542913643 + 1 + + + 0.39951984640520793 + 0.015753324583385513 + 0.5232499999999999 + 2.0 + 0.10290832458604321 + 2 + + + 0.5981852032210454 + 0.03869375083618437 + 0.5004999999999998 + 2.0 + 0.1504996567223901 + 3 + + + 0.795555923642033 + 0.07093616752652038 + 0.4777499999999998 + 2.0 + 0.1956045859691884 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.9898623304682607 + 0.1195757430653438 + 0.56875 + 2.0 + 0.26715081489516684 + 5 + + + + 0.19996431734333903 + 0.002671190386365311 + 0.56875 + 2.0 + 0.053430162979033385 + 1 + + + 0.3995006210438511 + 0.016017612161687976 + 0.56875 + 2.0 + 0.10686032595806677 + 2 + + + 0.5980394138922265 + 0.04000117326044228 + 0.56875 + 2.0 + 0.16029048893710013 + 3 + + + 0.7950140456781025 + 0.07455342212337938 + 0.56875 + 2.0 + 0.21372065191613349 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 0.9881911052608764 + 0.1277145242493972 + 0.6825000000000002 + 2.0 + 0.2988144911943945 + 5 + + + + 0.19996431734333903 + 0.002671190386365311 + 0.5915 + 2.0 + 0.05410474994108008 + 1 + + + 0.3994805062964411 + 0.016287693247577305 + 0.6142500000000001 + 2.0 + 0.1109487930447115 + 2 + + + 0.5978813201433568 + 0.041356187631243005 + 0.6370000000000001 + 2.0 + 0.17061824432895353 + 3 + + + 0.7944052377084674 + 0.07835332531831748 + 0.6597500000000002 + 2.0 + 0.23320641406492656 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.2095077927648281 + 0.1660343171670121 + 0.45499999999999974 + 3.000000000000001 + 0.28929725405972845 + 5 + + + + 0.20496253321050598 + 0.002804749905683577 + 0.5459999999999999 + 2.2 + 0.05406782712611742 + 1 + + + 0.42941535651290336 + 0.018168984194905872 + 0.5232499999999999 + 2.4000000000000004 + 0.11046255025713193 + 2 + + + 0.6724715109150357 + 0.04876555803228814 + 0.5004999999999998 + 2.6000000000000005 + 0.16874619415296394 + 3 + + + 0.9329750498944178 + 0.09721562208261593 + 0.4777499999999998 + 2.8000000000000007 + 0.22849487947501754 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.2066503615177901 + 0.17871886569577033 + 0.56875 + 3.000000000000001 + 0.3272597482465795 + 5 + + + + 0.20496253321050598 + 0.002804749905683577 + 0.56875 + 2.2 + 0.05476591705350922 + 1 + + + 0.4293906583172742 + 0.018492109970699007 + 0.56875 + 2.4000000000000004 + 0.11487485040492178 + 2 + + + 0.6722528499024035 + 0.05054739649540843 + 0.56875 + 2.6000000000000005 + 0.18032680005423768 + 3 + + + 0.9320351056498538 + 0.10267237968276068 + 0.56875 + 2.8000000000000007 + 0.2511217660014569 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.2032909332957593 + 0.19223095813513624 + 0.6825000000000002 + 3.000000000000001 + 0.3690127732957695 + 5 + + + + 0.20496253321050598 + 0.002804749905683577 + 0.5915 + 2.2 + 0.055474233363658254 + 1 + + + 0.429364787805472 + 0.01882239477798714 + 0.6142500000000001 + 2.4000000000000004 + 0.11944116348744918 + 2 + + + 0.6720148959937248 + 0.052395602264437305 + 0.6370000000000001 + 2.6000000000000005 + 0.19255418289439657 + 3 + + + 0.9309720187879943 + 0.10841212485694457 + 0.6597500000000002 + 2.8000000000000007 + 0.27550205633791464 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.4249610390514165 + 0.23004843568158873 + 0.45499999999999974 + 4.000000000000002 + 0.34031107425118295 + 5 + + + + 0.20996074907767293 + 0.0029383094250018424 + 0.5459999999999999 + 2.4000000000000004 + 0.05537033882309841 + 1 + + + 0.4592981397776713 + 0.020725378845376237 + 0.5232499999999999 + 2.8000000000000007 + 0.11801677592822063 + 2 + + + 0.746600036143376 + 0.05988780712873247 + 0.5004999999999998 + 3.200000000000001 + 0.1869927315835377 + 3 + + + 1.0695800259622146 + 0.12732328691144423 + 0.4777499999999998 + 3.6000000000000014 + 0.26138517298084657 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.4199855302048365 + 0.24895279590258573 + 0.56875 + 4.000000000000002 + 0.3873686815979921 + 5 + + + + 0.20996074907767293 + 0.0029383094250018424 + 0.56875 + 2.4000000000000004 + 0.05610167112798505 + 1 + + + 0.4592670924529283 + 0.02111290896394761 + 0.56875 + 2.8000000000000007 + 0.12288937485177678 + 2 + + + 0.746288440499 + 0.062214897723124996 + 0.56875 + 3.200000000000001 + 0.2003631111713752 + 3 + + + 1.0680886372351088 + 0.13498126973698618 + 0.56875 + 3.6000000000000014 + 0.2885228800867803 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.414096335315297 + 0.26908221511945096 + 0.6825000000000002 + 4.000000000000002 + 0.43921105539714445 + 5 + + + + 0.20996074907767293 + 0.0029383094250018424 + 0.5915 + 2.4000000000000004 + 0.056843716786236426 + 1 + + + 0.4592345381976442 + 0.021509099713464055 + 0.6142500000000001 + 2.8000000000000007 + 0.12793353393018686 + 2 + + + 0.7459483857582724 + 0.06463001943487043 + 0.6370000000000001 + 3.200000000000001 + 0.21449012145983962 + 3 + + + 1.0663936204005122 + 0.14304099025209366 + 0.6597500000000002 + 3.6000000000000014 + 0.31779769861090273 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.6372041531884638 + 0.3038307434300018 + 0.45499999999999974 + 4.999999999999998 + 0.39132489444263724 + 5 + + + + 0.21495896494483988 + 0.0030718689443201075 + 0.5459999999999999 + 2.5999999999999996 + 0.05667285052007939 + 1 + + + 0.48916748407693456 + 0.023422442895469728 + 0.5232499999999999 + 3.1999999999999993 + 0.12557100159930934 + 2 + + + 0.8205553432728554 + 0.07205806210939225 + 0.5004999999999998 + 3.799999999999999 + 0.20523926901411146 + 3 + + + 1.2052618902533148 + 0.16123434017046545 + 0.4777499999999998 + 4.399999999999999 + 0.2942754664866755 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.629284447630977 + 0.3300780859080193 + 0.56875 + 4.999999999999998 + 0.44747761494940447 + 5 + + + + 0.21495896494483988 + 0.0030718689443201075 + 0.56875 + 2.5999999999999996 + 0.05743742520246088 + 1 + + + 0.48912915076530483 + 0.023879935867887222 + 0.56875 + 3.1999999999999993 + 0.13090389929863178 + 2 + + + 0.8201284206423516 + 0.07500070885014831 + 0.56875 + 3.799999999999999 + 0.22039942228851267 + 3 + + + 1.2030419374172163 + 0.17144710762552837 + 0.56875 + 4.399999999999999 + 0.32592399417210355 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.6198675454729006 + 0.3579832278730878 + 0.6825000000000002 + 4.999999999999998 + 0.509409337498519 + 5 + + + + 0.21495896494483988 + 0.0030718689443201075 + 0.5915 + 2.5999999999999996 + 0.05821320020881459 + 1 + + + 0.48908892007316673 + 0.024347726361820327 + 0.6142500000000001 + 3.1999999999999993 + 0.1364259043729245 + 2 + + + 0.8196614126459395 + 0.07805583638423005 + 0.6370000000000001 + 3.799999999999999 + 0.23642606002528255 + 3 + + + 1.200509569591933 + 0.18219643240924435 + 0.6597500000000002 + 4.399999999999999 + 0.3600933408838906 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.56875 + 2.0 + 0.0 + 0 + + + 1.8457898451067947 + 0.3872229235940587 + 0.45499999999999974 + 6.000000000000001 + 0.4423387146340918 + 5 + + + + 0.21995718081200683 + 0.0032054284636383735 + 0.5459999999999999 + 2.8 + 0.05797536221706038 + 1 + + + 0.5190226776133118 + 0.026260107229932987 + 0.5232499999999999 + 3.5999999999999996 + 0.13312522727039802 + 2 + + + 0.8943220336476807 + 0.08527366243557918 + 0.5004999999999998 + 4.3999999999999995 + 0.22348580644468521 + 3 + + + 1.3399124279365746 + 0.1989208779949534 + 0.4777499999999998 + 5.2 + 0.3271657599925046 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.5474867015686742 + 0.04316307766755593 + 0.5687499999999998 + 2.7755575615628914e-16 + 0.17436703217063362 + 5 + + + + 0.18994807532245161 + 0.0030567541259597705 + 0.65975 + 1.6 + 0.06383982954667809 + 1 + + + 0.3395032101690863 + 0.014436336272080822 + 0.6369999999999999 + 1.2000000000000002 + 0.11194128663920108 + 2 + + + 0.44870255616930604 + 0.027645050238717047 + 0.6142499999999999 + 0.8000000000000003 + 0.14559193369831705 + 3 + + + 0.5179085927463465 + 0.03815017699622749 + 0.5914999999999998 + 0.4000000000000003 + 0.16601318754393646 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.5472664952424814 + 0.04471613006842177 + 0.6825 + 2.7755575615628914e-16 + 0.18683757382336133 + 5 + + + + 0.18994807532245161 + 0.0030567541259597705 + 0.6825 + 1.6 + 0.06454388913897936 + 1 + + + 0.33948726174332156 + 0.014628101036011061 + 0.6825 + 1.2000000000000002 + 0.11549959109080518 + 2 + + + 0.4486266145036203 + 0.028315884278744617 + 0.6825 + 0.8000000000000003 + 0.15286710585547744 + 3 + + + 0.5177455051550369 + 0.0393774118373324 + 0.6825 + 0.4000000000000003 + 0.17664643343299616 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.5470199151750713 + 0.04636381290456553 + 0.7962500000000002 + 2.7755575615628914e-16 + 0.2005207253261344 + 5 + + + + 0.18994807532245161 + 0.0030567541259597705 + 0.70525 + 1.6 + 0.06526108977589057 + 1 + + + 0.3394705494101036 + 0.014825061877472023 + 0.7280000000000001 + 1.2000000000000002 + 0.11920989827502962 + 2 + + + 0.44854457133063896 + 0.029015166616786908 + 0.7507500000000001 + 0.8000000000000003 + 0.16061808385889226 + 3 + + + 0.517565141057636 + 0.040671453349312776 + 0.7735000000000002 + 0.4000000000000003 + 0.18818343417123357 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.7681321104593459 + 0.08650246136048123 + 0.5687499999999998 + 0.9999999999999992 + 0.24021845492169747 + 5 + + + + 0.19494519061814336 + 0.003226573799624202 + 0.65975 + 1.7999999999999998 + 0.06549923852327777 + 1 + + + 0.3693715274649998 + 0.017152831243492456 + 0.6369999999999999 + 1.5999999999999996 + 0.1215924437358075 + 2 + + + 0.5229793208008218 + 0.037791970181004594 + 0.6142499999999999 + 1.3999999999999995 + 0.16897610292439036 + 3 + + + 0.6558174115407053 + 0.06181497300229381 + 0.5914999999999998 + 1.1999999999999993 + 0.20830950392871517 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.7672718220568406 + 0.09097510311154434 + 0.6825 + 0.9999999999999992 + 0.2632711267510999 + 5 + + + + 0.19494519061814336 + 0.003226573799624202 + 0.6825 + 1.7999999999999998 + 0.06624241253737355 + 1 + + + 0.369349745818339 + 0.017400527612090565 + 0.6825 + 1.5999999999999996 + 0.12569073148117033 + 2 + + + 0.5228440428896062 + 0.038849763201687385 + 0.6825 + 1.3999999999999995 + 0.17834495683139032 + 3 + + + 0.6554105000547117 + 0.06431663833810512 + 0.6825 + 1.1999999999999993 + 0.2242050885880335 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.7662757279732925 + 0.09578668703679602 + 0.7962500000000002 + 0.9999999999999992 + 0.2890298380931808 + 5 + + + + 0.19494519061814336 + 0.003226573799624202 + 0.70525 + 1.7999999999999998 + 0.06699945765411316 + 1 + + + 0.36932688573543543 + 0.01765505035456332 + 0.7280000000000001 + 1.5999999999999996 + 0.12996733418218273 + 2 + + + 0.5226969807903031 + 0.03995494973773272 + 0.7507500000000001 + 1.3999999999999995 + 0.1883544081649043 + 3 + + + 0.654953375816983 + 0.06697080032204555 + 0.7735000000000002 + 1.1999999999999993 + 0.24158035679726605 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.9857727134736003 + 0.14270854329818233 + 0.5687499999999998 + 2.0 + 0.3060698776727615 + 5 + + + + 0.19994230591383513 + 0.0033963934732886337 + 0.65975 + 2.0 + 0.06715864749987745 + 1 + + + 0.39922149168460536 + 0.020048616793082702 + 0.6369999999999999 + 2.0 + 0.13124360083241396 + 2 + + + 0.5970494599908549 + 0.0492810188154325 + 0.6142499999999999 + 2.0 + 0.19236027215046372 + 3 + + + 0.7927545440329061 + 0.09040075161947726 + 0.5914999999999998 + 2.0 + 0.250605820313494 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.9836404745062222 + 0.15154859601616077 + 0.6825 + 2.0 + 0.33970467967883883 + 5 + + + + 0.19994230591383513 + 0.0033963934732886337 + 0.6825 + 2.0 + 0.06794093593576775 + 1 + + + 0.39919274872193633 + 0.020358770180066446 + 0.6825 + 2.0 + 0.1358818718715355 + 2 + + + 0.5968319479376563 + 0.050808862398909145 + 0.6825 + 2.0 + 0.20382280780730327 + 3 + + + 0.7919479576672006 + 0.09460616745284361 + 0.6825 + 2.0 + 0.27176374374307105 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 0.981128850111913 + 0.161104736531221 + 0.7962500000000002 + 2.0 + 0.3775389508602273 + 5 + + + + 0.19994230591383513 + 0.0033963934732886337 + 0.70525 + 2.0 + 0.06873782553233576 + 1 + + + 0.39916254278370594 + 0.020677584630660058 + 0.7280000000000001 + 2.0 + 0.14072477008933582 + 2 + + + 0.5965943916396839 + 0.05240753127825955 + 0.7507500000000001 + 2.0 + 0.21609073247091645 + 3 + + + 0.7910328978121288 + 0.09908155007930368 + 0.7735000000000002 + 2.0 + 0.29497727942329866 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.1996499299171337 + 0.21157973796888746 + 0.5687499999999998 + 3.000000000000001 + 0.37192130042382554 + 5 + + + + 0.2049394212095269 + 0.003566213146953066 + 0.65975 + 2.2 + 0.06881805647647712 + 1 + + + 0.42905194551920967 + 0.023123571335707624 + 0.6369999999999999 + 2.4000000000000004 + 0.1408947579290204 + 2 + + + 0.670887752409929 + 0.06210805688515485 + 0.6142499999999999 + 2.6000000000000005 + 0.2157444413765371 + 3 + + + 0.9285403930973821 + 0.1238684882794876 + 0.5914999999999998 + 2.8000000000000007 + 0.29290213669827286 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.1954156923247679 + 0.22615739217761244 + 0.6825 + 3.000000000000001 + 0.41613823260657745 + 5 + + + + 0.2049394212095269 + 0.003566213146953066 + 0.6825 + 2.2 + 0.06963945933416194 + 1 + + + 0.42901502269658764 + 0.023502694388583937 + 0.6825 + 2.4000000000000004 + 0.14607301226190067 + 2 + + + 0.6705616299851976 + 0.06418824116806723 + 0.6825 + 2.6000000000000005 + 0.22930065878321618 + 3 + + + 0.9271425763519413 + 0.13019579132293307 + 0.6825 + 2.8000000000000007 + 0.31932239889810843 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.1903768254113953 + 0.24193163205055904 + 0.7962500000000002 + 3.000000000000001 + 0.4660480636272739 + 5 + + + + 0.2049394212095269 + 0.003566213146953066 + 0.70525 + 2.2 + 0.07047619341055836 + 1 + + + 0.42897617576729363 + 0.023892516273848304 + 0.7280000000000001 + 2.4000000000000004 + 0.15148220599648896 + 2 + + + 0.6702041742694512 + 0.06636701557256905 + 0.7507500000000001 + 2.6000000000000005 + 0.2438270567769286 + 3 + + + 0.9255460757916079 + 0.1369391423802398 + 0.7735000000000002 + 2.8000000000000007 + 0.34837420204933134 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.4090184068071556 + 0.2928700062348538 + 0.5687499999999998 + 4.000000000000002 + 0.4377727231748896 + 5 + + + + 0.20993653650521865 + 0.0037360328206174974 + 0.65975 + 2.4000000000000004 + 0.0704774654530768 + 1 + + + 0.45886173243292416 + 0.02637756607970173 + 0.6369999999999999 + 2.8000000000000007 + 0.15054591502562684 + 2 + + + 0.744469058091894 + 0.07626847587729457 + 0.6142499999999999 + 3.200000000000001 + 0.23912861060261045 + 3 + + + 1.0629969015385192 + 0.16217264287650024 + 0.5914999999999998 + 3.6000000000000014 + 0.33519845308305163 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.4016617333085346 + 0.31445841295815313 + 0.6825 + 4.000000000000002 + 0.4925717855343163 + 5 + + + + 0.20993653650521865 + 0.0037360328206174974 + 0.6825 + 2.4000000000000004 + 0.07133798273255613 + 1 + + + 0.4588153208735739 + 0.026832157800548026 + 0.6825 + 2.8000000000000007 + 0.15626415265226584 + 2 + + + 0.7440044938259397 + 0.0789823854465937 + 0.6825 + 3.200000000000001 + 0.2547785097591291 + 3 + + + 1.0607812552101157 + 0.17102665961885916 + 0.6825 + 3.6000000000000014 + 0.3668810540531459 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.3928504990312403 + 0.33778980832348404 + 0.7962500000000002 + 4.000000000000002 + 0.5545571763943205 + 5 + + + + 0.20993653650521865 + 0.0037360328206174974 + 0.70525 + 2.4000000000000004 + 0.07221456128878095 + 1 + + + 0.4587664409203708 + 0.027299687785355953 + 0.7280000000000001 + 2.8000000000000007 + 0.16223964190364207 + 2 + + + 0.7434938330610694 + 0.08182680736642986 + 0.7507500000000001 + 3.200000000000001 + 0.2715633810829407 + 3 + + + 1.058238418605966 + 0.1804675863124499 + 0.7735000000000002 + 3.6000000000000014 + 0.4017711246753639 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.6131486093659944 + 0.38628970882320585 + 0.5687499999999998 + 4.999999999999998 + 0.5036241459259533 + 5 + + + + 0.2149336518009104 + 0.0039058524942819288 + 0.65975 + 2.5999999999999996 + 0.07213687442967648 + 1 + + + 0.4886496967060723 + 0.029810465031616197 + 0.6369999999999999 + 3.1999999999999993 + 0.16019707212223327 + 2 + + + 0.817768327063499 + 0.09175719959537457 + 0.6142499999999999 + 3.799999999999999 + 0.26251277982868376 + 3 + + + 1.1959477868965502 + 0.2052612196623561 + 0.5914999999999998 + 4.399999999999999 + 0.37749476946783034 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.6014681194535911 + 0.4160462741725551 + 0.6825 + 4.999999999999998 + 0.5690053384620548 + 5 + + + + 0.2149336518009104 + 0.0039058524942819288 + 0.6825 + 2.5999999999999996 + 0.07303650613095032 + 1 + + + 0.48859239732364623 + 0.030347009898792923 + 0.6825 + 3.1999999999999993 + 0.16645529304263096 + 2 + + + 0.8171320600365849 + 0.09518520998291427 + 0.6825 + 3.799999999999999 + 0.2802563607350419 + 3 + + + 1.1926534391107726 + 0.2170313746562589 + 0.6825 + 4.399999999999999 + 0.4144397092081832 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.6825 + 2.0 + 0.0 + 0 + + + 1.5874209228172829 + 0.448113288814345 + 0.7962500000000002 + 4.999999999999998 + 0.6430662891613665 + 5 + + + + 0.2149336518009104 + 0.0039058524942819288 + 0.70525 + 2.5999999999999996 + 0.07395292916700354 + 1 + + + 0.48853199555798676 + 0.030898932606331985 + 0.7280000000000001 + 3.1999999999999993 + 0.17299707781079515 + 2 + + + 0.8164310212241852 + 0.09877961481080584 + 0.7507500000000001 + 3.799999999999999 + 0.29929970538895273 + 3 + + + 1.1888590801268184 + 0.2295796109201198 + 0.7735000000000002 + 4.399999999999999 + 0.4551680473013963 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.5460207186939378 + 0.05424438334553659 + 0.6824999999999998 + 2.7755575615628914e-16 + 0.21972943859360616 + 5 + + + + 0.18991792133134455 + 0.003842840544458611 + 0.7735 + 1.6 + 0.08028660125187723 + 1 + + + 0.33921429084969645 + 0.018147567785626765 + 0.7507499999999999 + 1.2000000000000002 + 0.14086047262182216 + 2 + + + 0.44794703209066855 + 0.034747233268183034 + 0.7279999999999999 + 0.8000000000000003 + 0.1833137492070107 + 3 + + + 0.5166894252019545 + 0.047946360247878704 + 0.7052499999999998 + 0.4000000000000003 + 0.209136808218683 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.5456830316826248 + 0.05613074028325602 + 0.79625 + 2.7755575615628914e-16 + 0.23491167182732275 + 5 + + + + 0.18991792133134455 + 0.003842840544458611 + 0.79625 + 1.6 + 0.08115130481307511 + 1 + + + 0.3391897032917016 + 0.018382360572157898 + 0.79625 + 1.2000000000000002 + 0.14521812440234494 + 2 + + + 0.44783023924706417 + 0.03556560437575426 + 0.79625 + 0.8000000000000003 + 0.1922004587678095 + 3 + + + 0.5164390822744735 + 0.049439191200983126 + 0.79625 + 0.4000000000000003 + 0.22209830790946877 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.5452990607794324 + 0.05816199542496559 + 0.9100000000000003 + 2.7755575615628914e-16 + 0.25197453122778446 + 5 + + + + 0.18991792133134455 + 0.003842840544458611 + 0.8190000000000001 + 1.6 + 0.0820363493694895 + 1 + + + 0.3391637649308377 + 0.018625169456664023 + 0.8417500000000001 + 1.2000000000000002 + 0.1498111284370543 + 2 + + + 0.4477027205074728 + 0.03642771672029826 + 0.8645000000000002 + 0.8000000000000003 + 0.20182423731707905 + 3 + + + 0.5161584164281269 + 0.05103445830869993 + 0.8872500000000002 + 0.4000000000000003 + 0.23646067883243177 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.7641207005561179 + 0.1086316342107082 + 0.6824999999999998 + 0.9999999999999992 + 0.30300456727273123 + 5 + + + + 0.19491336140530813 + 0.004056331685817423 + 0.7735 + 1.7999999999999998 + 0.08237412281811965 + 1 + + + 0.36900600174308756 + 0.021561562747868416 + 0.7507499999999999 + 1.5999999999999996 + 0.15301302090218993 + 2 + + + 0.5218024287394226 + 0.04749250119718329 + 0.7279999999999999 + 1.3999999999999995 + 0.2127935495533461 + 3 + + + 0.6533779492851862 + 0.07765520429767603 + 0.7052499999999998 + 1.1999999999999993 + 0.2625348367568488 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.7628059761065845 + 0.11402648723036196 + 0.79625 + 0.9999999999999992 + 0.3310119012112273 + 5 + + + + 0.19491336140530813 + 0.004056331685817423 + 0.79625 + 1.7999999999999998 + 0.08328686546605077 + 1 + + + 0.368972425715807 + 0.021864744647483742 + 0.79625 + 1.5999999999999996 + 0.1580314883201989 + 2 + + + 0.5215945160630654 + 0.048781154294905774 + 0.79625 + 1.3999999999999995 + 0.22423386856244434 + 3 + + + 0.6527543753694334 + 0.08068764970562006 + 0.79625 + 1.1999999999999993 + 0.28189400619278715 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.7612546944132699 + 0.11993470679065256 + 0.9100000000000003 + 0.9999999999999992 + 0.3632183826391684 + 5 + + + + 0.19491336140530813 + 0.004056331685817423 + 0.8190000000000001 + 1.7999999999999998 + 0.08422107916448818 + 1 + + + 0.3689369469202097 + 0.022178452850741597 + 0.8417500000000001 + 1.5999999999999996 + 0.16332605013751691 + 2 + + + 0.5213659613198698 + 0.05014252131036204 + 0.8645000000000002 + 1.3999999999999995 + 0.23666657479774542 + 3 + + + 0.6520431453434891 + 0.08395262591041155 + 0.8872500000000002 + 1.1999999999999993 + 0.30354713539568096 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.9774651339738771 + 0.1789995801776416 + 0.6824999999999998 + 2.0 + 0.3862796959518565 + 5 + + + + 0.19990880147927173 + 0.004269822827176235 + 0.7735 + 2.0 + 0.0844616443843621 + 1 + + + 0.3987686858532337 + 0.02520049709212962 + 0.7507499999999999 + 2.0 + 0.16516556918255776 + 2 + + + 0.5953309756005802 + 0.061916474035312516 + 0.7279999999999999 + 2.0 + 0.24227334989968158 + 3 + + + 0.788529133024924 + 0.11349744363445549 + 0.7052499999999998 + 2.0 + 0.3159328652950148 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.9742162567816172 + 0.1895850694021321 + 0.79625 + 2.0 + 0.4271121305951321 + 5 + + + + 0.19990880147927173 + 0.004269822827176235 + 0.79625 + 2.0 + 0.08542242611902644 + 1 + + + 0.3987243848102241 + 0.025580011015633612 + 0.79625 + 2.0 + 0.17084485223805287 + 2 + + + 0.5949968764582726 + 0.06377515885041854 + 0.79625 + 2.0 + 0.2562672783570793 + 3 + + + 0.7872949485242667 + 0.11857672612322645 + 0.79625 + 2.0 + 0.3416897044761057 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 0.9703116094861575 + 0.20123885806975256 + 0.9100000000000003 + 2.0 + 0.47446223405055266 + 5 + + + + 0.19990880147927173 + 0.004269822827176235 + 0.8190000000000001 + 2.0 + 0.08640580895948685 + 1 + + + 0.3986775075954039 + 0.02597287377768818 + 0.8417500000000001 + 2.0 + 0.17684097183797956 + 2 + + + 0.5946277743015373 + 0.0657422418087466 + 0.8645000000000002 + 2.0 + 0.2715089122784119 + 3 + + + 0.785872330837004 + 0.12406482599258206 + 0.8872500000000002 + 2.0 + 0.3706335919589303 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.1848695414864916 + 0.2649457259716523 + 0.6824999999999998 + 3.000000000000001 + 0.4695548246309818 + 5 + + + + 0.2049042415532353 + 0.0044833139685350465 + 0.7735 + 2.2 + 0.08654916595060455 + 1 + + + 0.42850051605270423 + 0.02906412880636645 + 0.7507499999999999 + 2.4000000000000004 + 0.17731811746292558 + 2 + + + 0.6684929657046582 + 0.07801090441336897 + 0.7279999999999999 + 2.6000000000000005 + 0.27175315024601704 + 3 + + + 0.9218613001780668 + 0.1553952452264153 + 0.7052499999999998 + 2.8000000000000007 + 0.36933089383318074 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.1784382189518892 + 0.2822560724403603 + 0.79625 + 3.000000000000001 + 0.523212359979037 + 5 + + + + 0.2049042415532353 + 0.0044833139685350465 + 0.79625 + 2.2 + 0.0875579867720021 + 1 + + + 0.4284436147119981 + 0.029527892941546872 + 0.79625 + 2.4000000000000004 + 0.18365821615590686 + 2 + + + 0.667992339594215 + 0.08053782610793203 + 0.79625 + 2.6000000000000005 + 0.2883006881517143 + 3 + + + 0.9197257661519336 + 0.16300715117796916 + 0.79625 + 2.8000000000000007 + 0.40148540275942435 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.1706270677007498 + 0.301315633191891 + 0.9100000000000003 + 3.000000000000001 + 0.5857060854619368 + 5 + + + + 0.2049042415532353 + 0.0044833139685350465 + 0.8190000000000001 + 2.2 + 0.08859053875448555 + 1 + + + 0.42838333116762756 + 0.03000813804555926 + 0.8417500000000001 + 2.4000000000000004 + 0.19035589353844226 + 2 + + + 0.6674371466698665 + 0.08321522353433046 + 0.8645000000000002 + 2.6000000000000005 + 0.30635124975907835 + 3 + + + 0.9172466874879175 + 0.1712438148259909 + 0.8872500000000002 + 2.8000000000000007 + 0.4377200485221797 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.3851827653862094 + 0.36598033635115473 + 0.6824999999999998 + 4.000000000000002 + 0.5528299533101071 + 5 + + + + 0.2098996816271989 + 0.004696805109893859 + 0.7735 + 2.4000000000000004 + 0.088636687516847 + 1 + + + 0.4581996671500129 + 0.03315220156088031 + 0.7507499999999999 + 2.8000000000000007 + 0.18947066574329338 + 2 + + + 0.7412488962877946 + 0.09576661499339022 + 0.7279999999999999 + 3.200000000000001 + 0.3012329505923525 + 3 + + + 1.053096646452556 + 0.2032579168049915 + 0.7052499999999998 + 3.6000000000000014 + 0.42272892237134674 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.3740481921579777 + 0.39136604615137977 + 0.79625 + 4.000000000000002 + 0.6193125893629416 + 5 + + + + 0.2098996816271989 + 0.004696805109893859 + 0.79625 + 2.4000000000000004 + 0.08969354742497776 + 1 + + + 0.4581281517767152 + 0.03370810767526047 + 0.79625 + 2.8000000000000007 + 0.1964715800737608 + 2 + + + 0.7405361848360772 + 0.09905823542838033 + 0.79625 + 3.200000000000001 + 0.32033409794634915 + 3 + + + 1.0497172582231529 + 0.2138627966151555 + 0.79625 + 3.6000000000000014 + 0.4612811010427428 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.3604403051665028 + 0.4192319902071056 + 0.9100000000000003 + 4.000000000000002 + 0.6969499368733211 + 5 + + + + 0.2098996816271989 + 0.004696805109893859 + 0.8190000000000001 + 2.4000000000000004 + 0.09077526854948423 + 1 + + + 0.4580523043926205 + 0.0342839335408843 + 0.8417500000000001 + 2.8000000000000007 + 0.20387081523890488 + 2 + + + 0.7397433982570594 + 0.10254843941129271 + 0.8645000000000002 + 3.200000000000001 + 0.3411935872397448 + 3 + + + 1.0457746956343077 + 0.22534017288828456 + 0.8872500000000002 + 3.6000000000000014 + 0.504806505085429 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.5772933544583534 + 0.4815291480801713 + 0.6824999999999998 + 4.999999999999998 + 0.636105081989232 + 5 + + + + 0.21489512170116248 + 0.0049102962512526695 + 0.7735 + 2.5999999999999996 + 0.09072420908308942 + 1 + + + 0.48786431599814356 + 0.037464444723256274 + 0.7507499999999999 + 3.1999999999999993 + 0.20162321402366115 + 2 + + + 0.8135594903202015 + 0.11517350343979202 + 0.7279999999999999 + 3.799999999999999 + 0.3307127509386879 + 3 + + + 1.1819618226114819 + 0.25698209671669525 + 0.7052499999999998 + 4.399999999999999 + 0.47612695090951246 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.79625 + 2.0 + 0.0 + 0 + + + 1.559684701244536 + 0.5161233336486863 + 0.79625 + 4.999999999999998 + 0.7154128187468461 + 5 + + + + 0.21489512170116248 + 0.0049102962512526695 + 0.79625 + 2.5999999999999996 + 0.09182910807795341 + 1 + + + 0.4877760347046518 + 0.03812035646970094 + 0.79625 + 3.1999999999999993 + 0.20928494399161474 + 2 + + + 0.8125839797590627 + 0.1193243442659716 + 0.79625 + 3.799999999999999 + 0.35236750774098397 + 3 + + + 1.1769461638221739 + 0.2710109719011351 + 0.79625 + 4.399999999999999 + 0.5210767993260611 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.543715003587392 + 0.06806874275335362 + 0.7962499999999998 + 2.7755575615628914e-16 + 0.27625040325578915 + 5 + + + + 0.18986996206853002 + 0.0048363124176357295 + 0.88725 + 1.6 + 0.10102958463976686 + 1 + + + 0.3387567073537767 + 0.022816935101560867 + 0.8644999999999999 + 1.2000000000000002 + 0.17717150262727316 + 2 + + + 0.4467545285122479 + 0.04364669146457786 + 0.8417499999999999 + 0.8000000000000003 + 0.23050400521562958 + 3 + + + 0.5147697322100474 + 0.060184880812789505 + 0.8189999999999998 + 0.4000000000000003 + 0.26294061356055204 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.5431705407017031 + 0.07047253692575203 + 0.91 + 2.7755575615628914e-16 + 0.2956948523816157 + 5 + + + + 0.18986996206853002 + 0.0048363124176357295 + 0.91 + 1.6 + 0.10214913082273996 + 1 + + + 0.3387167484572299 + 0.0231195420231047 + 0.91 + 1.2000000000000002 + 0.18279318147227153 + 2 + + + 0.44656541379039255 + 0.0446960105557401 + 0.91 + 0.8000000000000003 + 0.2419321519485947 + 3 + + + 0.5143655079363427 + 0.06209119072208999 + 0.91 + 0.4000000000000003 + 0.2795660422517094 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.757844922625646 + 0.13601516371467026 + 0.7962499999999998 + 0.9999999999999992 + 0.3808820623399246 + 5 + + + + 0.19486273773900392 + 0.005104996440837714 + 0.88725 + 1.7999999999999998 + 0.10365552265125272 + 1 + + + 0.36842731322162275 + 0.027105621117906632 + 0.8644999999999999 + 1.5999999999999996 + 0.19244857436023144 + 2 + + + 0.5199472468878369 + 0.05962476413760387 + 0.8417499999999999 + 1.3999999999999995 + 0.2675482906315688 + 3 + + + 0.6495478460628379 + 0.09735808876022331 + 0.8189999999999998 + 1.1999999999999993 + 0.33002904427921986 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.7557364890971123 + 0.14281842782129053 + 0.91 + 0.9999999999999992 + 0.41666092835591284 + 5 + + + + 0.19486273773900392 + 0.005104996440837714 + 0.91 + 1.7999999999999998 + 0.104837265844391 + 1 + + + 0.3683727590335474 + 0.027496188183773182 + 0.91 + 1.5999999999999996 + 0.19892199160217777 + 2 + + + 0.5196109394096422 + 0.061273625387931574 + 0.91 + 1.3999999999999995 + 0.28225417727336033 + 3 + + + 0.6485436328366112 + 0.10121003881080026 + 0.91 + 1.1999999999999993 + 0.3548338228579387 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.964527372408017 + 0.22353471155117943 + 0.7962499999999998 + 2.0 + 0.48551372142406024 + 5 + + + + 0.1998555134094778 + 0.005373680464039699 + 0.88725 + 2.0 + 0.10628146066273861 + 1 + + + 0.3980520736298553 + 0.03167581445500065 + 0.8644999999999999 + 2.0 + 0.20772564609318978 + 2 + + + 0.5926252245103785 + 0.07768986868577912 + 0.8417499999999999 + 2.0 + 0.30459257604750817 + 3 + + + 0.7819118720761165 + 0.14210007524591023 + 0.8189999999999998 + 2.0 + 0.39711747499788774 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 0.9593418846292603 + 0.23673251371992277 + 0.91 + 2.0 + 0.5376270043302102 + 5 + + + + 0.1998555134094778 + 0.005373680464039699 + 0.91 + 2.0 + 0.10752540086604206 + 1 + + + 0.39798010921862426 + 0.03216448518054476 + 0.91 + 2.0 + 0.21505080173208413 + 2 + + + 0.5920853340890059 + 0.08006296490500106 + 0.91 + 2.0 + 0.32257620259812614 + 3 + + + 0.7799291607344703 + 0.14851586457392868 + 0.91 + 2.0 + 0.43010160346416815 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 1.161953363198212 + 0.32983741220832974 + 0.7962499999999998 + 3.000000000000001 + 0.5901453805081959 + 5 + + + + 0.2048482890799517 + 0.005642364487241684 + 0.88725 + 2.2 + 0.1089073986742245 + 1 + + + 0.42762811395376105 + 0.036527034506263246 + 0.8644999999999999 + 2.4000000000000004 + 0.2230027178261481 + 2 + + + 0.6647265083633256 + 0.09782568919917506 + 0.8417499999999999 + 2.6000000000000005 + 0.34163686146344757 + 3 + + + 0.9114267200969159 + 0.1942574683891465 + 0.8189999999999998 + 2.8000000000000007 + 0.4642059057165558 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 1.1517403783579003 + 0.35113136244382065 + 0.91 + 3.000000000000001 + 0.6585930803045078 + 5 + + + + 0.2048482890799517 + 0.005642364487241684 + 0.91 + 2.2 + 0.11021353588769311 + 1 + + + 0.42753570083705106 + 0.03712390197159193 + 0.91 + 2.4000000000000004 + 0.23117961186199043 + 2 + + + 0.6639183022155932 + 0.1010445885579756 + 0.91 + 2.6000000000000005 + 0.362898227922892 + 3 + + + 0.9080045514987474 + 0.20381233230388754 + 0.91 + 2.8000000000000007 + 0.5053693840703978 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 1.3483958460315864 + 0.45396730232298027 + 0.7962499999999998 + 4.000000000000002 + 0.6947770395923316 + 5 + + + + 0.2098410647504256 + 0.005911048510443669 + 0.88725 + 2.4000000000000004 + 0.11153333668571036 + 1 + + + 0.4571525644026194 + 0.04165877234566082 + 0.8644999999999999 + 2.8000000000000007 + 0.23827978955910645 + 2 + + + 0.736189652904419 + 0.12001408879199697 + 0.8417499999999999 + 3.200000000000001 + 0.3786811468793869 + 3 + + + 1.0376668736121497 + 0.25365203973004274 + 0.8189999999999998 + 3.6000000000000014 + 0.5312943364352237 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 1.330813991388169 + 0.4846983412274598 + 0.91 + 4.000000000000002 + 0.7795591562788052 + 5 + + + + 0.2098410647504256 + 0.005911048510443669 + 0.91 + 2.4000000000000004 + 0.11290167090934417 + 1 + + + 0.45703644127279575 + 0.04237387575205505 + 0.91 + 2.8000000000000007 + 0.2473084219918968 + 2 + + + 0.7350401981072044 + 0.1241968390736867 + 0.91 + 3.200000000000001 + 0.4032202532476578 + 3 + + + 1.0322658509216913 + 0.2668704845187368 + 0.91 + 3.6000000000000014 + 0.5806371646766273 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.91 + 2.0 + 0.0 + 0 + + + 1.5222248368262385 + 0.5948107838860703 + 0.7962499999999998 + 4.999999999999998 + 0.7994086986764666 + 5 + + + + 0.21483384042089948 + 0.006179732533645653 + 0.88725 + 2.5999999999999996 + 0.11415927469719625 + 1 + + + 0.48662256028957407 + 0.04707049077460692 + 0.8644999999999999 + 3.1999999999999993 + 0.2535568612920647 + 2 + + + 0.8069537729687992 + 0.14423512512112746 + 0.8417499999999999 + 3.799999999999999 + 0.4157254322953261 + 3 + + + 1.1602177998483287 + 0.3200812932039411 + 0.8189999999999998 + 4.399999999999999 + 0.5983827671538913 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 3.0 + 0.0 + 0 + + + 0.8250000000000003 + 0.0 + 0.0 + 2.220446049250313e-16 + 0.0 + 5 + + + + 0.28500000000000003 + 0.0 + 0.0 + 2.4000000000000004 + 0.0 + 1 + + + 0.51 + 0.0 + 0.0 + 1.8000000000000005 + 0.0 + 2 + + + 0.6750000000000002 + 0.0 + 0.0 + 1.2000000000000004 + 0.0 + 3 + + + 0.7800000000000002 + 0.0 + 0.0 + 0.6000000000000003 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 3.0 + 0.0 + 0 + + + 0.8249929592363636 + 0.002189789199339075 + 0.11374999999999999 + 2.220446049250313e-16 + 0.011781515898131074 + 5 + + + + 0.28500000000000003 + 0.0 + 0.022750000000000003 + 2.4000000000000004 + 0.0006418289262476647 + 1 + + + 0.5099998083801247 + 0.0002642349755384942 + 0.045500000000000006 + 1.8000000000000005 + 0.0032811236066607394 + 2 + + + 0.6749983887554448 + 0.0009340671855514514 + 0.06825 + 1.2000000000000004 + 0.006778481642312266 + 3 + + + 0.7799953875350064 + 0.0017229360040094091 + 0.091 + 0.6000000000000003 + 0.009993323110339689 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 3.0 + 0.0 + 0 + + + 1.0499999999999998 + 0.0 + 0.0 + 0.9999999999999996 + 0.0 + 5 + + + + 0.29000000000000004 + 0.0 + 0.0 + 2.5999999999999996 + 0.0 + 1 + + + 0.54 + 0.0 + 0.0 + 2.1999999999999993 + 0.0 + 2 + + + 0.75 + 0.0 + 0.0 + 1.7999999999999994 + 0.0 + 3 + + + 0.9199999999999999 + 0.0 + 0.0 + 1.3999999999999995 + 0.0 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 3.0 + 0.0 + 0 + + + 1.0499760296692862 + 0.004755942223604847 + 0.11374999999999999 + 0.9999999999999996 + 0.018571856431851747 + 5 + + + + 0.29000000000000004 + 0.0 + 0.022750000000000003 + 2.5999999999999996 + 0.0006656003679605411 + 1 + + + 0.5399997541757339 + 0.00031475294144539014 + 0.045500000000000006 + 2.1999999999999993 + 0.0036140099507811496 + 2 + + + 0.7499974071863261 + 0.001283015203066814 + 0.06825 + 1.7999999999999994 + 0.008086859329514954 + 3 + + + 0.9199899205993007 + 0.0028634530923985504 + 0.091 + 1.3999999999999995 + 0.013325985183189944 + 4 + + + + + 10 + + 0.0 + 0.0 + 0.0 + 3.0 + 0.0 + 0 + + + 1.275 + 0.0 + 0.0 + 1.9999999999999991 + 0.0 + 5 + + + + 0.29500000000000004 + 0.0 + 0.0 + 2.8 + 0.0 + 1 + + + 0.5700000000000001 + 0.0 + 0.0 + 2.5999999999999996 + 0.0 + 2 + + + 0.825